mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-03 11:14:08 +05:30
added L298 Motor Driver
This commit is contained in:
parent
641e015b4e
commit
8523223ca6
@ -61,6 +61,9 @@
|
|||||||
|
|
||||||
/* Encoders directly attached to Arduino board */
|
/* Encoders directly attached to Arduino board */
|
||||||
//#define ARDUINO_ENC_COUNTER
|
//#define ARDUINO_ENC_COUNTER
|
||||||
|
|
||||||
|
/* L298 Motor driver*/
|
||||||
|
//#define L298_MOTOR_DRIVER
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_SERVOS // Enable use of PWM servos as defined in servos.h
|
#define USE_SERVOS // Enable use of PWM servos as defined in servos.h
|
||||||
|
@ -2,6 +2,15 @@
|
|||||||
Motor driver function definitions - by James Nugen
|
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 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);
|
||||||
|
@ -51,6 +51,37 @@
|
|||||||
}
|
}
|
||||||
|
|
||||||
// A convenience function for setting both motor speeds
|
// 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) {
|
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||||
setMotorSpeed(LEFT, leftSpeed);
|
setMotorSpeed(LEFT, leftSpeed);
|
||||||
setMotorSpeed(RIGHT, rightSpeed);
|
setMotorSpeed(RIGHT, rightSpeed);
|
||||||
|
Loading…
x
Reference in New Issue
Block a user