Added support for Arduino Motor Shield R3

This commit is contained in:
Patrick Goebel 2016-01-27 06:26:10 -08:00
parent 5933239b70
commit f7c01d41c5
2 changed files with 62 additions and 1 deletions

View File

@ -5,3 +5,4 @@
void initMotorController();
void setMotorSpeed(int i, int spd);
void setMotorSpeeds(int leftSpeed, int rightSpeed);

View File

@ -55,8 +55,68 @@
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
#elif defined ARDUINO_MOTOR_SHIELD_R3
/* Include the pin definitions for the shield */
#include "arduino_motor_shield_r3.h"
/* Wrap the motor driver initialization */
void initMotorController() {
// Set up Channel A - LEFT
pinMode(LEFT_MOTOR_PIN_DIR, OUTPUT); // Initiates Motor Channel A pin
pinMode(LEFT_MOTOR_PIN_BRAKE, OUTPUT); // Initiates Brake Channel A pin
// Set up Channel B - RIGHT
pinMode(RIGHT_MOTOR_PIN_DIR, OUTPUT); // Initiates Motor Channel B pin
pinMode(RIGHT_MOTOR_PIN_BRAKE, OUTPUT); // Initiates Brake Channel B pin
}
/* Wrap the drive motor set speed function */
void setMotorSpeed(int i, int spd) {
if (i == LEFT) {
if (spd < 0) digitalWrite(LEFT_MOTOR_PIN_DIR, LOW);
else digitalWrite(LEFT_MOTOR_PIN_DIR, HIGH);
if (spd == 0) digitalWrite(LEFT_MOTOR_PIN_BRAKE, HIGH);
else digitalWrite(LEFT_MOTOR_PIN_BRAKE, LOW);
analogWrite(LEFT_MOTOR_PIN_SPEED, spd);
}
else {
if (spd < 0) digitalWrite(RIGHT_MOTOR_PIN_DIR, LOW);
else digitalWrite(RIGHT_MOTOR_PIN_DIR, HIGH);
if (spd == 0) digitalWrite(RIGHT_MOTOR_PIN_BRAKE, HIGH);
else digitalWrite(RIGHT_MOTOR_PIN_BRAKE, LOW);
analogWrite(RIGHT_MOTOR_PIN_SPEED, spd);
}
}
/* A convenience function for setting both motor speeds */
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
/* For testing only! */
#elif defined(NO_MOTOR_CONTROLLER)
/* Wrap the motor driver initialization */
void initMotorController() { }
/* A convenience function for setting both motor speeds */
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
setMotorSpeed(LEFT, leftSpeed);
setMotorSpeed(RIGHT, rightSpeed);
}
/* Wrap the drive motor set speed function */
void setMotorSpeed(int i, int spd) {
if (i == LEFT) {}
else {}
}
#else
#error A motor driver must be selected!
//#error A motor driver must be selected!
#endif
#endif