mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-03 03:04:09 +05:30
Merge pull request #44 from AnasIbrahim/ADDING_L298_MOTOR_DRIVER_INDIGO
Adding l298 motor driver indigo
This commit is contained in:
commit
a960c8a88a
18
README.md
18
README.md
@ -26,6 +26,8 @@ the PC. The base controller requires the use of a motor controller and encoders
|
||||
|
||||
**NOTE:** The Robogaia Mega Encoder shield can only be used with an Arduino Mega. The on-board wheel encoder counters are currently only supported by Arduino Uno.
|
||||
|
||||
* L298 motor driver
|
||||
|
||||
* The library can be easily extended to include support for other motor controllers and encoder hardware or libraries.
|
||||
|
||||
Official ROS Documentation
|
||||
@ -67,6 +69,8 @@ The Robogaia Mega Encoder library can be found at:
|
||||
|
||||
http://www.robogaia.com/uploads/6/8/0/9/6809982/__megaencodercounter-1.3.tar.gz
|
||||
|
||||
L298 Motor Driver doesn't require any libraries
|
||||
|
||||
These libraries should be installed in your standard Arduino
|
||||
sketchbook/libraries directory.
|
||||
|
||||
@ -148,7 +152,7 @@ still want to try the code, see the notes at the end of the file.
|
||||
|
||||
Choose one of the supported motor controllers by uncommenting its #define statement and commenting out any others. By default, the Pololu VNH5019 driver is chosen.
|
||||
|
||||
Choose a supported encoder library by by uncommenting its #define statement and commenting out any others. At the moment, only the Robogaia Mega Encoder shield is supported and it is chosen by default.
|
||||
Choose a supported encoder library by by uncommenting its #define statement and commenting out any others. the Robogaia Mega Encoder shield is chosen by default.
|
||||
|
||||
If you want to control PWM servos attached to your controller, look for the line:
|
||||
|
||||
@ -461,6 +465,18 @@ Make the following changes in the ROSArduinoBridge sketch to disable the RoboGai
|
||||
|
||||
Compile the changes and upload to your controller.
|
||||
|
||||
Using L298 Motor driver
|
||||
-----------------------
|
||||
the wiring between the L298 motor driver and arduino board is defined in motor_driver.h in the firmware as follow:
|
||||
|
||||
#define RIGHT_MOTOR_BACKWARD 5
|
||||
#define LEFT_MOTOR_BACKWARD 6
|
||||
#define RIGHT_MOTOR_FORWARD 9
|
||||
#define LEFT_MOTOR_FORWARD 10
|
||||
#define RIGHT_MOTOR_ENABLE 12
|
||||
#define LEFT_MOTOR_ENABLE 13
|
||||
|
||||
wire them this way or change them if you want, and make sure that the L298 motor driver is defined then compile and upload the firmware.
|
||||
|
||||
NOTES
|
||||
-----
|
||||
|
@ -61,6 +61,9 @@
|
||||
|
||||
/* Encoders directly attached to Arduino board */
|
||||
//#define ARDUINO_ENC_COUNTER
|
||||
|
||||
/* L298 Motor driver*/
|
||||
//#define L298_MOTOR_DRIVER
|
||||
#endif
|
||||
|
||||
#define USE_SERVOS // Enable use of PWM servos as defined in servos.h
|
||||
|
@ -2,6 +2,15 @@
|
||||
Motor driver function definitions - by James Nugen
|
||||
*************************************************************/
|
||||
|
||||
#ifdef L298_MOTOR_DRIVER
|
||||
#define RIGHT_MOTOR_BACKWARD 5
|
||||
#define LEFT_MOTOR_BACKWARD 6
|
||||
#define RIGHT_MOTOR_FORWARD 9
|
||||
#define LEFT_MOTOR_FORWARD 10
|
||||
#define RIGHT_MOTOR_ENABLE 12
|
||||
#define LEFT_MOTOR_ENABLE 13
|
||||
#endif
|
||||
|
||||
void initMotorController();
|
||||
void setMotorSpeed(int i, int spd);
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed);
|
||||
|
@ -51,6 +51,37 @@
|
||||
}
|
||||
|
||||
// A convenience function for setting both motor speeds
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||
setMotorSpeed(LEFT, leftSpeed);
|
||||
setMotorSpeed(RIGHT, rightSpeed);
|
||||
}
|
||||
#elif defined L298_MOTOR_DRIVER
|
||||
void initMotorController() {
|
||||
digitalWrite(RIGHT_MOTOR_ENABLE, HIGH);
|
||||
digitalWrite(LEFT_MOTOR_ENABLE, HIGH);
|
||||
}
|
||||
|
||||
void setMotorSpeed(int i, int spd) {
|
||||
unsigned char reverse = 0;
|
||||
|
||||
if (spd < 0)
|
||||
{
|
||||
spd = -spd;
|
||||
reverse = 1;
|
||||
}
|
||||
if (spd > 255)
|
||||
spd = 255;
|
||||
|
||||
if (i == LEFT) {
|
||||
if (reverse == 0) { analogWrite(RIGHT_MOTOR_FORWARD, spd); analogWrite(RIGHT_MOTOR_BACKWARD, 0); }
|
||||
else if (reverse == 1) { analogWrite(RIGHT_MOTOR_BACKWARD, spd); analogWrite(RIGHT_MOTOR_FORWARD, 0); }
|
||||
}
|
||||
else /*if (i == RIGHT) //no need for condition*/ {
|
||||
if (reverse == 0) { analogWrite(LEFT_MOTOR_FORWARD, spd); analogWrite(LEFT_MOTOR_BACKWARD, 0); }
|
||||
else if (reverse == 1) { analogWrite(LEFT_MOTOR_BACKWARD, spd); analogWrite(LEFT_MOTOR_FORWARD, 0); }
|
||||
}
|
||||
}
|
||||
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||
setMotorSpeed(LEFT, leftSpeed);
|
||||
setMotorSpeed(RIGHT, rightSpeed);
|
||||
|
Loading…
x
Reference in New Issue
Block a user