mirror of
https://github.com/YikeStone/ros_arduino_bridge.git
synced 2025-08-03 11:14:08 +05:30
Incorporated changes from James Nugen into ROSArduinoBridge library
This commit is contained in:
parent
01cca86e40
commit
849cb2ec83
@ -9,6 +9,9 @@
|
||||
different motor controller or encoder method.
|
||||
|
||||
Created for the Pi Robot Project: http://www.pirobot.org
|
||||
and the Home Brew Robotics Club (HBRC): http://hbrobotics.org
|
||||
|
||||
Authors: Patrick Goebel, James Nugen
|
||||
|
||||
Inspired and modeled after the ArbotiX driver by Michael Ferguson
|
||||
|
||||
@ -50,6 +53,9 @@
|
||||
/* The Pololu VNH5019 dual motor driver shield */
|
||||
#define POLOLU_VNH5019
|
||||
|
||||
/* The Pololu MC33926 dual motor driver shield */
|
||||
//#define POLOLU_MC33926
|
||||
|
||||
/* The RoboGaia encoder shield */
|
||||
#define ROBOGAIA
|
||||
#endif
|
||||
@ -82,27 +88,11 @@
|
||||
#endif
|
||||
|
||||
#ifdef USE_BASE
|
||||
#ifdef POLOLU_VNH5019
|
||||
/* Include the Pololu library */
|
||||
#include "DualVNH5019MotorShield.h"
|
||||
#endif
|
||||
|
||||
/* Include the motor driver functions */
|
||||
/* Motor driver function definitions */
|
||||
#include "motor_driver.h"
|
||||
|
||||
#ifdef ROBOGAIA
|
||||
/* The Robogaia Mega Encoder shield */
|
||||
#include "MegaEncoderCounter.h"
|
||||
#endif
|
||||
|
||||
/* Include the encoder functions */
|
||||
#include "encoders.h"
|
||||
|
||||
/* Wrap the encoder reset function */
|
||||
void resetEncoders() {
|
||||
resetEncoder(LEFT);
|
||||
resetEncoder(RIGHT);
|
||||
}
|
||||
/* Encoder driver function definitions */
|
||||
#include "encoder_driver.h"
|
||||
|
||||
/* PID parameters and functions */
|
||||
#include "diff_controller.h"
|
||||
|
@ -0,0 +1,8 @@
|
||||
/* *************************************************************
|
||||
Encoder driver function definitions - by James Nugen
|
||||
************************************************************ */
|
||||
|
||||
long readEncoder(int i);
|
||||
void resetEncoder(int i);
|
||||
void resetEncoders();
|
||||
|
@ -1,15 +1,18 @@
|
||||
|
||||
|
||||
/* *************************************************************
|
||||
Encoder definitions
|
||||
|
||||
Add a #ifdef block to this file to include support for
|
||||
a particular encoder board or library. Then add the appropriate #define
|
||||
near the top of the main ROSArduinoBridge.ino file.
|
||||
Add a "#if defined" block to this file to include support for
|
||||
a particular encoder board or library. Then add the appropriate
|
||||
#define near the top of the main ROSArduinoBridge.ino file.
|
||||
|
||||
************************************************************ */
|
||||
|
||||
#ifdef ROBOGAIA
|
||||
#ifdef USE_BASE
|
||||
|
||||
#if defined ROBOGAIA
|
||||
/* The Robogaia Mega Encoder shield */
|
||||
#include "MegaEncoderCounter.h"
|
||||
|
||||
/* Create the encoder shield object */
|
||||
MegaEncoderCounter encoders = MegaEncoderCounter(4); // Initializes the Mega Encoder Counter in the 4X Count mode
|
||||
|
||||
@ -24,5 +27,15 @@
|
||||
if (i == LEFT) return encoders.YAxisReset();
|
||||
else return encoders.XAxisReset();
|
||||
}
|
||||
#else
|
||||
#error A encoder driver must be selected!
|
||||
#endif
|
||||
|
||||
/* Wrap the encoder reset function */
|
||||
void resetEncoders() {
|
||||
resetEncoder(LEFT);
|
||||
resetEncoder(RIGHT);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@ -1,32 +1,7 @@
|
||||
/***************************************************************
|
||||
Motor driver definitions
|
||||
|
||||
Add a #ifdef block to this file to include support for
|
||||
a particular motor driver. Then add the appropriate #define
|
||||
near the top of the main ROSArduinoBridge.ino file.
|
||||
|
||||
Motor driver function definitions - by James Nugen
|
||||
*************************************************************/
|
||||
|
||||
#ifdef POLOLU_VNH5019
|
||||
/* Create the motor driver object */
|
||||
DualVNH5019MotorShield drive;
|
||||
|
||||
/* Wrap the motor driver initialization */
|
||||
void initMotorController() {
|
||||
drive.init();
|
||||
}
|
||||
|
||||
/* Wrap the drive motor set speed function */
|
||||
void setMotorSpeed(int i, int spd) {
|
||||
if (i == LEFT) drive.setM1Speed(spd);
|
||||
else drive.setM2Speed(spd);
|
||||
}
|
||||
|
||||
// A convenience function for setting both motor speeds
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||
setMotorSpeed(LEFT, leftSpeed);
|
||||
setMotorSpeed(RIGHT, rightSpeed);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
void initMotorController();
|
||||
void setMotorSpeed(int i, int spd);
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed);
|
||||
|
@ -0,0 +1,62 @@
|
||||
/***************************************************************
|
||||
Motor driver definitions
|
||||
|
||||
Add a "#elif defined" block to this file to include support
|
||||
for a particular motor driver. Then add the appropriate
|
||||
#define near the top of the main ROSArduinoBridge.ino file.
|
||||
|
||||
*************************************************************/
|
||||
|
||||
#ifdef USE_BASE
|
||||
|
||||
#if defined POLOLU_VNH5019
|
||||
/* Include the Pololu library */
|
||||
#include "DualVNH5019MotorShield.h"
|
||||
|
||||
/* Create the motor driver object */
|
||||
DualVNH5019MotorShield drive;
|
||||
|
||||
/* Wrap the motor driver initialization */
|
||||
void initMotorController() {
|
||||
drive.init();
|
||||
}
|
||||
|
||||
/* Wrap the drive motor set speed function */
|
||||
void setMotorSpeed(int i, int spd) {
|
||||
if (i == LEFT) drive.setM1Speed(spd);
|
||||
else drive.setM2Speed(spd);
|
||||
}
|
||||
|
||||
// A convenience function for setting both motor speeds
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||
setMotorSpeed(LEFT, leftSpeed);
|
||||
setMotorSpeed(RIGHT, rightSpeed);
|
||||
}
|
||||
#elif defined POLOLU_MC33926
|
||||
/* Include the Pololu library */
|
||||
#include "DualMC33926MotorShield.h"
|
||||
|
||||
/* Create the motor driver object */
|
||||
DualMC33926MotorShield drive;
|
||||
|
||||
/* Wrap the motor driver initialization */
|
||||
void initMotorController() {
|
||||
drive.init();
|
||||
}
|
||||
|
||||
/* Wrap the drive motor set speed function */
|
||||
void setMotorSpeed(int i, int spd) {
|
||||
if (i == LEFT) drive.setM1Speed(spd);
|
||||
else drive.setM2Speed(spd);
|
||||
}
|
||||
|
||||
// A convenience function for setting both motor speeds
|
||||
void setMotorSpeeds(int leftSpeed, int rightSpeed) {
|
||||
setMotorSpeed(LEFT, leftSpeed);
|
||||
setMotorSpeed(RIGHT, rightSpeed);
|
||||
}
|
||||
#else
|
||||
#error A motor driver must be selected!
|
||||
#endif
|
||||
|
||||
#endif
|
Loading…
x
Reference in New Issue
Block a user