TI RSLK Library  0.2.0
Romi_Motor_Power.cpp
1 #include "Romi_Motor_Power.h"
2 
3 Romi_Motor_Power::Romi_Motor_Power()
4 {
5  slp_pin = 0;
6  dir_pin = 0;
7  pwm_pin = 0;
8  motor_dir = 0;
9  preserve_speed = 0;
10 }
11 
12 bool Romi_Motor_Power::begin(uint8_t _slp_pin, uint8_t _dir_pin,uint8_t _pwm_pin) {
13  slp_pin = _slp_pin;
14  dir_pin = _dir_pin;
15  pwm_pin = _pwm_pin;
16 
17  pinMode(slp_pin, OUTPUT);
18  pinMode(dir_pin, OUTPUT);
19  pinMode(pwm_pin, OUTPUT);
20 
21  disableMotor();
22 }
23 
25  setRawSpeed(0);
26  digitalWrite(slp_pin, LOW);
27 }
28 
30  digitalWrite(slp_pin, HIGH);
31 }
32 
34  digitalWrite(dir_pin, LOW);
35 }
36 
38  digitalWrite(dir_pin, HIGH);
39 }
40 
42  disableMotor();
43 }
44 
46  setRawSpeed(preserve_speed);
47  enableMotor();
48 }
49 
50 void Romi_Motor_Power::setSpeed(uint8_t speed) {
51  speed = map(speed, 0, 100, 0, 255);
52  setRawSpeed(speed);
53 }
54 
55 void Romi_Motor_Power::setRawSpeed(uint8_t speed) {
56  preserve_speed = speed;
57  analogWrite(pwm_pin, speed);
58 }
Romi_Motor_Power::directionForward
void directionForward()
Set motor's direction to forward.
Definition: Romi_Motor_Power.cpp:33
Romi_Motor_Power::setSpeed
void setSpeed(uint8_t speed)
Set motor speed.
Definition: Romi_Motor_Power.cpp:50
Romi_Motor_Power::enableMotor
void enableMotor()
Enable motor.
Definition: Romi_Motor_Power.cpp:29
Romi_Motor_Power::resumeMotor
void resumeMotor()
Resume motor.
Definition: Romi_Motor_Power.cpp:45
Romi_Motor_Power::begin
bool begin(uint8_t islp_pin, uint8_t idir_pin, uint8_t ipwm_pin)
Initialize the motor and configures important pins.
Definition: Romi_Motor_Power.cpp:12
Romi_Motor_Power::directionBackward
void directionBackward()
Set motor's direction to backwards.
Definition: Romi_Motor_Power.cpp:37
Romi_Motor_Power::pauseMotor
void pauseMotor()
Pause motor.
Definition: Romi_Motor_Power.cpp:41
Romi_Motor_Power::disableMotor
void disableMotor()
Disable motor.
Definition: Romi_Motor_Power.cpp:24
Romi_Motor_Power::setRawSpeed
void setRawSpeed(uint8_t speed)
Set motor's raw speed.
Definition: Romi_Motor_Power.cpp:55