TI RSLK Library 0.2.2
Loading...
Searching...
No Matches
Romi_Motor_Power.cpp
1#include "Romi_Motor_Power.h"
2
3Romi_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
12bool Romi_Motor_Power::begin(uint8_t _slp_pin, uint8_t _dir_pin, uint8_t _pwm_pin)
13{
14 slp_pin = _slp_pin;
15 dir_pin = _dir_pin;
16 pwm_pin = _pwm_pin;
17
18 pinMode(slp_pin, OUTPUT);
19 pinMode(dir_pin, OUTPUT);
20 pinMode(pwm_pin, OUTPUT);
21
23
24 return true;
25}
26
28{
29 setRawSpeed(0);
30 digitalWrite(slp_pin, LOW);
31}
32
34{
35 digitalWrite(slp_pin, HIGH);
36}
37
39{
40 digitalWrite(dir_pin, LOW);
41}
42
44{
45 digitalWrite(dir_pin, HIGH);
46}
47
49{
50 // disable motor without affecting preserve_speed
51 analogWrite(pwm_pin, 0);
52 digitalWrite(slp_pin, LOW);
53}
54
56{
57 setRawSpeed(preserve_speed);
59}
60
61void Romi_Motor_Power::setSpeed(uint8_t speed)
62{
63 speed = map(speed, 0, 100, 0, 255);
64 setRawSpeed(speed);
65}
66
68{
69 preserve_speed = speed;
70 analogWrite(pwm_pin, speed);
71}
void disableMotor()
Disable motor.
void directionForward()
Set motor's direction to forward.
void pauseMotor()
Pause motor.
void resumeMotor()
Resume motor.
void setRawSpeed(uint8_t speed)
Set motor's raw speed.
void setSpeed(uint8_t speed)
Set motor speed.
bool begin(uint8_t islp_pin, uint8_t idir_pin, uint8_t ipwm_pin)
Initialize the motor and configures important pins.
void enableMotor()
Enable motor.
void directionBackward()
Set motor's direction to backwards.