1#include "Romi_Motor_Power.h"
3Romi_Motor_Power::Romi_Motor_Power()
18 pinMode(slp_pin, OUTPUT);
19 pinMode(dir_pin, OUTPUT);
20 pinMode(pwm_pin, OUTPUT);
30 digitalWrite(slp_pin, LOW);
35 digitalWrite(slp_pin, HIGH);
40 digitalWrite(dir_pin, LOW);
45 digitalWrite(dir_pin, HIGH);
51 analogWrite(pwm_pin, 0);
52 digitalWrite(slp_pin, LOW);
63 speed = map(speed, 0, 100, 0, 255);
69 preserve_speed = speed;
70 analogWrite(pwm_pin, speed);
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.