arduino stuffs
| -rw-r--r-- | car_driver/arduino/arduino.ino | 14 | ||||
| -rw-r--r-- | car_driver/arduino/drive.h | 18 | ||||
| -rw-r--r-- | car_driver/arduino/drive.ino | 57 | ||||
| -rw-r--r-- | car_driver/arduino/motor.h | 30 | ||||
| -rw-r--r-- | car_driver/arduino/motor_utils.h | 18 |
5 files changed, 74 insertions, 63 deletions
diff --git a/car_driver/arduino/arduino.ino b/car_driver/arduino/arduino.ino index 8e231da..5be4b2d 100644 --- a/car_driver/arduino/arduino.ino +++ b/car_driver/arduino/arduino.ino @@ -6,6 +6,8 @@ const int MOVE_RIGHT[2] = {1, 0}; // move right const int MOVE_BACK[2] = {0, 1}; // move back const int MOVE_STOP[2] = {0, 0}; // stop +#include "drive.h" + void setup() { Serial.begin(9600); Serial.println("initialized"); @@ -35,21 +37,21 @@ void processCommand(const int x, const int y) { } if (x < DEADZONE && x >= 0) { // apply brakes to motora - brakeMotorA(); + motor_a.brake(); } else if (x < 0) { - motorABackward(abs(x) + 155); + motor_a.backward(abs(x) + 155); } else { // positive number: 100 + 155 = 255 - motorAForward(x + 155); + motor_a.forward(x + 155); } if (y < DEADZONE && y >= 0) { // apply brakes to motorb - brakeMotorB(); + motor_b.brake(); } else if (y < 0) { // negative number: -100 + 355 = 255 - motorBBackward(abs(y) + 155); + motor_b.backward(abs(y) + 155); } else { // apply speed to motorb - motorBForward(y + 155); + motor_b.forward(y + 155); } Serial.print("x: "); Serial.print(String(x)); diff --git a/car_driver/arduino/drive.h b/car_driver/arduino/drive.h new file mode 100644 index 0000000..1850ce9 --- /dev/null +++ b/car_driver/arduino/drive.h @@ -0,0 +1,18 @@ +#ifndef DRIVE_H +#define DRIVE_H + +#include "motor.h" + +Motor motor_b(13, 8, 11); +Motor motor_a(12, 9, 3); + +inline void begin() { + motor_a.begin(); + motor_b.begin(); +} + +inline void stop() { + motor_a.brake(); + motor_b.brake(); +} +#endif
\ No newline at end of file diff --git a/car_driver/arduino/drive.ino b/car_driver/arduino/drive.ino deleted file mode 100644 index 4ced292..0000000 --- a/car_driver/arduino/drive.ino +++ /dev/null @@ -1,57 +0,0 @@ -#define MotorA 12 // left motor -#define BrakeMotorA 9 -#define MotorASpeed 3 - -#define MotorB 13 // right motor -#define BrakeMotorB 8 -#define MotorBSpeed 11 - -void begin() { - // Setup Channel A - pinMode(MotorA, OUTPUT); - pinMode(BrakeMotorA, OUTPUT); - - // Setup Channel B - pinMode(MotorB, OUTPUT); - pinMode(BrakeMotorB, OUTPUT); -} - -// @param direction LOW is backwards, HIGH is forward -// @param speed 0-255 -void motor(int motorpin, int motorbrake, int motorspeed, int direction, - int speed) { - digitalWrite(motorpin, direction); - digitalWrite(motorbrake, LOW); // brake off - analogWrite(motorspeed, speed); // speed up -} - -void motorAForward(int speed) { - motor(MotorA, BrakeMotorA, MotorASpeed, HIGH, speed); -} - -void motorBForward(int speed) { - motor(MotorB, BrakeMotorB, MotorBSpeed, HIGH, speed); -} - -void motorBBackward(int speed) { - motor(MotorB, BrakeMotorB, MotorBSpeed, LOW, speed); -} - -void motorABackward(int speed) { - motor(MotorA, BrakeMotorA, MotorASpeed, LOW, speed); -} - -void brakeMotorA() { - digitalWrite(brakeMotorA, HIGH); // engage brake - analogWrite(MotorASpeed, 0); // slow -} - -void brakeMotorB() { - digitalWrite(brakeMotorB, HIGH); // engage brake - analogWrite(MotorBSpeed, 0); // slow -} - -void stop() { - brakeMotorA(); - brakeMotorB(); -}
\ No newline at end of file diff --git a/car_driver/arduino/motor.h b/car_driver/arduino/motor.h new file mode 100644 index 0000000..f2f0f43 --- /dev/null +++ b/car_driver/arduino/motor.h @@ -0,0 +1,30 @@ +#ifndef MOTOR_H +#define MOTOR_H + +#include "motor_utils.h" + +struct Motor { + int pin; + int brake_pin; + int speed_pin; + + inline void forward(int speed) { + motor_utils::set(pin, brake_pin, speed_pin, HIGH, speed); + } + inline void backward(int speed) { + motor_utils::set(pin, brake_pin, speed_pin, LOW, speed); + } + inline void brake() { motor_utils::brake(brake_pin, speed_pin); } + + inline void begin() { + pinMode(pin, OUTPUT); + pinMode(brake_pin, OUTPUT); + } + + Motor(const int _pin, const int _brake_pin, const int _speed_pin) { + pin = _pin; + brake_pin = _brake_pin; + speed_pin = _speed_pin; + } +}; +#endif
\ No newline at end of file diff --git a/car_driver/arduino/motor_utils.h b/car_driver/arduino/motor_utils.h new file mode 100644 index 0000000..fea6441 --- /dev/null +++ b/car_driver/arduino/motor_utils.h @@ -0,0 +1,18 @@ +#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(int motor, int brake, int speed_pin, int direction, int speed) { + digitalWrite(motor, direction); + digitalWrite(brake, LOW); // brake off + analogWrite(speed_pin, speed); // speed up +} + +inline void brake(int brake_pin, int speed_pin) { + digitalWrite(brake_pin, HIGH); // engage brake + analogWrite(speed_pin, 0); // slow +} +} // namespace motor_utils +#endif
\ No newline at end of file |