TI RSLK Library
0.2.0
src
Romi_Motor_Power.h
1
#ifndef Romi_Motor_Power_h
2
#define Romi_Motor_Power_h
3
4
#include "Energia.h"
5
13
14
15
class
Romi_Motor_Power
16
{
17
private
:
18
uint8_t slp_pin;
19
uint8_t dir_pin;
20
uint8_t pwm_pin;
21
uint8_t motor_dir;
22
uint8_t sleep_speed;
23
uint8_t preserve_speed;
24
25
public
:
26
Romi_Motor_Power
();
27
35
bool
begin
(uint8_t islp_pin, uint8_t idir_pin,uint8_t ipwm_pin);
36
42
void
disableMotor
();
43
48
void
enableMotor
();
49
50
56
void
pauseMotor
();
57
63
void
resumeMotor
();
64
68
void
directionForward
();
69
73
void
directionBackward
();
74
83
void
setSpeed
(uint8_t speed);
84
93
void
setRawSpeed
(uint8_t speed);
94
};
95
96
#endif
97
98
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
Represents a single motor.
Definition:
Romi_Motor_Power.h:15
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
Generated by
1.8.16