TI RSLK Library 0.2.2
Loading...
Searching...
No Matches
Romi_Motor_Power.h
1#ifndef Romi_Motor_Power_h
2#define Romi_Motor_Power_h
3
4#include "Energia.h"
5
13
15{
16private:
17 uint8_t slp_pin;
18 uint8_t dir_pin;
19 uint8_t pwm_pin;
20 uint8_t motor_dir;
21 uint8_t sleep_speed;
22 uint8_t preserve_speed;
23
24public:
26
34 bool begin(uint8_t islp_pin, uint8_t idir_pin, uint8_t ipwm_pin);
35
41 void disableMotor();
42
47 void enableMotor();
48
54 void pauseMotor();
55
61 void resumeMotor();
62
66 void directionForward();
67
71 void directionBackward();
72
81 void setSpeed(uint8_t speed);
82
91 void setRawSpeed(uint8_t speed);
92};
93
94#endif
Represents a single motor.
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.