TI RSLK Library
0.2.0
|
Represents a single motor. More...
#include <Romi_Motor_Power.h>
Public Member Functions | |
bool | begin (uint8_t islp_pin, uint8_t idir_pin, uint8_t ipwm_pin) |
Initialize the motor and configures important pins. More... | |
void | disableMotor () |
Disable motor. More... | |
void | enableMotor () |
Enable motor. More... | |
void | pauseMotor () |
Pause motor. More... | |
void | resumeMotor () |
Resume motor. More... | |
void | directionForward () |
Set motor's direction to forward. More... | |
void | directionBackward () |
Set motor's direction to backwards. More... | |
void | setSpeed (uint8_t speed) |
Set motor speed. More... | |
void | setRawSpeed (uint8_t speed) |
Set motor's raw speed. More... | |
Represents a single motor.
An instance of this class represents a single motor. The function begin() must be called before using any other function.
Parts:
Definition at line 15 of file Romi_Motor_Power.h.
bool Romi_Motor_Power::begin | ( | uint8_t | islp_pin, |
uint8_t | idir_pin, | ||
uint8_t | ipwm_pin | ||
) |
Initialize the motor and configures important pins.
[in] | islp_pin | pin number on Launchpad connected to motor's sleep pin |
[in] | idir_pin | pin number on Launchpad connected to motor's direction pin |
[in] | ipwm_pin | pin number on Launchpad connected to motor's PWM pin |
Call this function to initialize motor
Definition at line 12 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::directionBackward | ( | ) |
Set motor's direction to backwards.
Spins the wheel in the backward direction.
Definition at line 37 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::directionForward | ( | ) |
Set motor's direction to forward.
Spins the wheel in the forward direction.
Definition at line 33 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::disableMotor | ( | ) |
Disable motor.
This function with disable the motor by putting it to sleep. The motor's speed is also set to 0. After calling this function the motor needs to be reenabled and be given a speed before it will start working again.
Definition at line 24 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::enableMotor | ( | ) |
Enable motor.
This function with enable the motor by taking it out of sleep. The motor's speed needs to be reenabled to start working again.
Definition at line 29 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::pauseMotor | ( | ) |
Pause motor.
This function with stop the motor and acts just like disableMotor. However, the motor's speed when pause will be preserved and restored once resumeMotor is called.
Definition at line 41 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::resumeMotor | ( | ) |
Resume motor.
This function with resume the motor's operation if pauseMotor was previously called. Unlike enableMotor the motor will start running based on the speed that was set when the motor was paused.
Definition at line 45 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::setRawSpeed | ( | uint8_t | speed | ) |
Set motor's raw speed.
[in] | speed | between 0 - 255
|
Sets the motor speed. Provides finer grain control of the motor's speed then setSpeed.
Definition at line 55 of file Romi_Motor_Power.cpp.
void Romi_Motor_Power::setSpeed | ( | uint8_t | speed | ) |
Set motor speed.
[in] | speed | Valid values are 0 - 100 mimicing percentage.
|
Sets the motor speed. This function may be easier for beginners to understand.
Definition at line 50 of file Romi_Motor_Power.cpp.