mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-07 04:44:07 +05:30
Added support for Adafruit Motor Shield V2 and Arduino Motor Shield V3
This commit is contained in:
parent
453eae91b5
commit
038e0cf9b4
@ -6,3 +6,38 @@ void initMotorController();
|
|||||||
void setMotorSpeed(int i, int spd);
|
void setMotorSpeed(int i, int spd);
|
||||||
void setMotorSpeeds(int leftSpeed, int rightSpeed);
|
void setMotorSpeeds(int leftSpeed, int rightSpeed);
|
||||||
|
|
||||||
|
|
||||||
|
/**********
|
||||||
|
* Pin assignments for the Arduino Motor Shield R3
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef ARDUINO_MOTOR_SHIELD_R3
|
||||||
|
|
||||||
|
#define LEFT_MOTOR_PIN_DIR 12
|
||||||
|
#define LEFT_MOTOR_PIN_BRAKE 9
|
||||||
|
#define LEFT_MOTOR_PIN_SPEED 3
|
||||||
|
|
||||||
|
#define RIGHT_MOTOR_PIN_DIR 13
|
||||||
|
#define RIGHT_MOTOR_PIN_BRAKE 8
|
||||||
|
#define RIGHT_MOTOR_PIN_SPEED 11
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ADAFRUIT_MOTOR_SHIELD_V2
|
||||||
|
|
||||||
|
#define LEFT_MOTOR_HEADER 1
|
||||||
|
#define RIGHT_MOTOR_HEADER 2
|
||||||
|
|
||||||
|
#include <Wire.h>
|
||||||
|
#include <Adafruit_MotorShield.h>
|
||||||
|
|
||||||
|
// Create the motor shield object with the default I2C address
|
||||||
|
Adafruit_MotorShield AFMS = Adafruit_MotorShield();
|
||||||
|
// Or, create it with a different I2C address (say for stacking)
|
||||||
|
// Adafruit_MotorShield AFMS = Adafruit_MotorShield(0x61);
|
||||||
|
|
||||||
|
// Select which 'port' M1, M2, M3 or M4. NOTE: M1 and M2 conflict with the Robogaia 3-axis encoder shield.
|
||||||
|
Adafruit_DCMotor *myLeftMotor = AFMS.getMotor(LEFT_MOTOR_HEADER);
|
||||||
|
Adafruit_DCMotor *myRightMotor = AFMS.getMotor(RIGHT_MOTOR_HEADER);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
@ -32,6 +32,7 @@
|
|||||||
setMotorSpeed(LEFT, leftSpeed);
|
setMotorSpeed(LEFT, leftSpeed);
|
||||||
setMotorSpeed(RIGHT, rightSpeed);
|
setMotorSpeed(RIGHT, rightSpeed);
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif defined POLOLU_MC33926
|
#elif defined POLOLU_MC33926
|
||||||
/* Include the Pololu library */
|
/* Include the Pololu library */
|
||||||
#include "DualMC33926MotorShield.h"
|
#include "DualMC33926MotorShield.h"
|
||||||
@ -55,19 +56,53 @@
|
|||||||
setMotorSpeed(LEFT, leftSpeed);
|
setMotorSpeed(LEFT, leftSpeed);
|
||||||
setMotorSpeed(RIGHT, rightSpeed);
|
setMotorSpeed(RIGHT, rightSpeed);
|
||||||
}
|
}
|
||||||
#elif defined ARDUINO_MOTOR_SHIELD_R3
|
|
||||||
/* Include the pin definitions for the shield */
|
|
||||||
#include "arduino_motor_shield_r3.h"
|
|
||||||
|
|
||||||
|
#elif defined ADAFRUIT_MOTOR_SHIELD_V2
|
||||||
/* Wrap the motor driver initialization */
|
/* Wrap the motor driver initialization */
|
||||||
void initMotorController() {
|
void initMotorController() {
|
||||||
|
AFMS.begin();
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Wrap the drive motor set speed function */
|
||||||
|
void setMotorSpeed(int i, int spd) {
|
||||||
|
if (i == LEFT) {
|
||||||
|
if (spd < 0) {
|
||||||
|
myLeftMotor->run(BACKWARD);
|
||||||
|
spd = -spd;
|
||||||
|
}
|
||||||
|
else myLeftMotor->run(FORWARD);
|
||||||
|
myLeftMotor->setSpeed(spd);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (spd < 0) {
|
||||||
|
myRightMotor->run(BACKWARD);
|
||||||
|
spd = -spd;
|
||||||
|
}
|
||||||
|
else myRightMotor->run(FORWARD);
|
||||||
|
myRightMotor->setSpeed(spd);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// A convenience function for setting both motor speeds
|
||||||
|
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||||
|
setMotorSpeed(LEFT, leftSpeed);
|
||||||
|
setMotorSpeed(RIGHT, rightSpeed);
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif defined ARDUINO_MOTOR_SHIELD_R3
|
||||||
|
/* Wrap the motor driver initialization */
|
||||||
|
void initMotorController() {
|
||||||
|
/* If the brake function is enabled */
|
||||||
|
#ifdef USE_ARDUINO_MOTOR_SHIELD_R3_BRAKE
|
||||||
|
pinMode(LEFT_MOTOR_PIN_BRAKE, OUTPUT); // Initiates Brake Channel A pin
|
||||||
|
pinMode(RIGHT_MOTOR_PIN_BRAKE, OUTPUT); // Initiates Brake Channel B pin
|
||||||
|
#endif
|
||||||
|
|
||||||
// Set up Channel A - LEFT
|
// Set up Channel A - LEFT
|
||||||
pinMode(LEFT_MOTOR_PIN_DIR, OUTPUT); // Initiates Motor Channel A pin
|
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
|
// Set up Channel B - RIGHT
|
||||||
pinMode(RIGHT_MOTOR_PIN_DIR, OUTPUT); // Initiates Motor Channel B pin
|
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 */
|
/* Wrap the drive motor set speed function */
|
||||||
@ -76,8 +111,10 @@
|
|||||||
if (spd < 0) digitalWrite(LEFT_MOTOR_PIN_DIR, LOW);
|
if (spd < 0) digitalWrite(LEFT_MOTOR_PIN_DIR, LOW);
|
||||||
else digitalWrite(LEFT_MOTOR_PIN_DIR, HIGH);
|
else digitalWrite(LEFT_MOTOR_PIN_DIR, HIGH);
|
||||||
|
|
||||||
|
#ifdef USE_ARDUINO_MOTOR_SHIELD_R3_BRAKE
|
||||||
if (spd == 0) digitalWrite(LEFT_MOTOR_PIN_BRAKE, HIGH);
|
if (spd == 0) digitalWrite(LEFT_MOTOR_PIN_BRAKE, HIGH);
|
||||||
else digitalWrite(LEFT_MOTOR_PIN_BRAKE, LOW);
|
else digitalWrite(LEFT_MOTOR_PIN_BRAKE, LOW);
|
||||||
|
#endif
|
||||||
|
|
||||||
analogWrite(LEFT_MOTOR_PIN_SPEED, spd);
|
analogWrite(LEFT_MOTOR_PIN_SPEED, spd);
|
||||||
}
|
}
|
||||||
@ -85,8 +122,10 @@
|
|||||||
if (spd < 0) digitalWrite(RIGHT_MOTOR_PIN_DIR, LOW);
|
if (spd < 0) digitalWrite(RIGHT_MOTOR_PIN_DIR, LOW);
|
||||||
else digitalWrite(RIGHT_MOTOR_PIN_DIR, HIGH);
|
else digitalWrite(RIGHT_MOTOR_PIN_DIR, HIGH);
|
||||||
|
|
||||||
|
#ifdef USE_ARDUINO_MOTOR_SHIELD_R3_BRAKE
|
||||||
if (spd == 0) digitalWrite(RIGHT_MOTOR_PIN_BRAKE, HIGH);
|
if (spd == 0) digitalWrite(RIGHT_MOTOR_PIN_BRAKE, HIGH);
|
||||||
else digitalWrite(RIGHT_MOTOR_PIN_BRAKE, LOW);
|
else digitalWrite(RIGHT_MOTOR_PIN_BRAKE, LOW);
|
||||||
|
#endif
|
||||||
|
|
||||||
analogWrite(RIGHT_MOTOR_PIN_SPEED, spd);
|
analogWrite(RIGHT_MOTOR_PIN_SPEED, spd);
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user