arduino stuffs
better motors
| -rw-r--r-- | car_driver/arduino/drive.h | 32 | ||||
| -rw-r--r-- | car_driver/arduino/motor.h | 36 | ||||
| -rw-r--r-- | car_driver/arduino/motor_utils.h | 19 |
3 files changed, 58 insertions, 29 deletions
diff --git a/car_driver/arduino/drive.h b/car_driver/arduino/drive.h index 1850ce9..89a42b3 100644 --- a/car_driver/arduino/drive.h +++ b/car_driver/arduino/drive.h @@ -11,8 +11,38 @@ inline void begin() { motor_b.begin(); } -inline void stop() { +inline void brake() { motor_a.brake(); motor_b.brake(); } + +inline void forward(uint8_t speed) { + motor_a.forward(speed); + motor_b.forward(speed); +} + +inline void forward(uint8_t a_speed, uint8_t b_speed) { + motor_a.forward(a_speed); + motor_b.forward(b_speed); +} + +inline void backward(uint8_t speed) { + motor_a.backward(speed); + motor_b.backward(speed); +} + +inline void backward(uint8_t a_speed, uint8_t b_speed) { + motor_a.backward(a_speed); + motor_b.backward(b_speed); +} + +inline void speed(int8_t speed) { + motor_a.speed(speed); + motor_b.speed(speed); +} + +inline void speed(uint8_t a_speed, uint8_t b_speed) { + motor_a.speed(a_speed); + motor_b.speed(b_speed); +} #endif
\ No newline at end of file diff --git a/car_driver/arduino/motor.h b/car_driver/arduino/motor.h index cfc05e4..cc57f72 100644 --- a/car_driver/arduino/motor.h +++ b/car_driver/arduino/motor.h @@ -1,22 +1,40 @@ #ifndef MOTOR_H #define MOTOR_H -#include "motor_utils.h" - -struct Motor { +class Motor { +private: int pin; int brake_pin; int speed_pin; - inline void forward(int8_t speed) { - motor_utils::set(pin, brake_pin, speed_pin, HIGH, speed); + // @param direction LOW is backwards, HIGH is forward + // @param speed 0-255 + void set(int8_t direction, uint8_t speed) { + digitalWrite(pin, direction); + digitalWrite(brake_pin, LOW); // brake off + analogWrite(speed_pin, speed); // speed up } - inline void backward(int8_t speed) { - motor_utils::set(pin, brake_pin, speed_pin, LOW, speed); + +public: + // @param speed -100-100, the speed to go at, negative = backwards + void speed(int8_t speed) { + if (speed == 0) + brake(); + else if (speed < 0) + backward(abs(speed) + 155); // negative number: -100 + 355 = 255 + else + forward(speed + 155); // positive number: 100 + 155 = 255 } - inline void brake() { motor_utils::brake(brake_pin, speed_pin); } - inline void begin() { + void brake() { + digitalWrite(brake_pin, HIGH); // engage brake + analogWrite(speed_pin, 0); // slow + } + + inline void forward(uint8_t speed) { set(HIGH, speed); } + inline void backward(uint8_t speed) { set(LOW, speed); } + + void begin() { pinMode(pin, OUTPUT); pinMode(brake_pin, OUTPUT); } diff --git a/car_driver/arduino/motor_utils.h b/car_driver/arduino/motor_utils.h deleted file mode 100644 index cb40b1b..0000000 --- a/car_driver/arduino/motor_utils.h +++ /dev/null @@ -1,19 +0,0 @@ -#ifndef MOTOR_UTILS_H -#define MOTOR_UTILS_H - -namespace motor_utils { -// @param direction LOW is backwards, HIGH is forward -// @param speed 0-255 -inline void set(uint8_t motor_pin, uint8_t brake_pin, uint8_t speed_pin, - int8_t direction, uint8_t speed) { - digitalWrite(motor_pin, direction); - digitalWrite(brake_pin, LOW); // brake off - analogWrite(speed_pin, speed); // speed up -} - -inline void brake(uint8_t brake_pin, uint8_t speed_pin) { - digitalWrite(brake_pin, HIGH); // engage brake - analogWrite(speed_pin, 0); // slow -} -} // namespace motor_utils -#endif
\ No newline at end of file |