abdrive library
v0.5.5
Differential servo and encoder drive library for the Parallax ActivityBot
|
This library takes care of encoder monitoring and servo signalling, and provides a simple set of functions for making the ActivityBot go certain distances and speeds.
For more information, go here:
http://learn.parallax.com/activitybot/navigation-basics
Please submit bug reports, suggestions, and improvements to this code to edito.
r@pa ralla x.co mMore...
#include "simpletools.h"
#include "simpletext.h"
#include "fdserial.h"
Go to the source code of this file.
Macros | |
#define | _ActivityBot_EE_Start_ 63418 |
ActivityBot EEPROM calibration data start address. | |
#define | _ActivityBot_EE_Pins_ 12 |
#define | _ActivityBot_EE_Trims_ 28 |
#define | _ActivityBot_EE_Left_ 52 |
#define | _ActivityBot_EE_Right_ 1052 |
#define | _ActivityBot_EE_End_ 63418 + 2052 |
ActivityBot EEPROM calibration data end address. | |
#define | AB_RIGHT 1 |
#define | AB_LEFT -1 |
#define | AB_FORWARD 1 |
#define | AB_BACKWARD -1 |
#define | OFF 0 |
OFF can be used in place of zero to enabled parameters in functions like drive_feedback and drive_trim. | |
#define | ON 1 |
ON can be used in place of a nonzero value to enabled parameters in functions like drive_feedback and drive_trim. |
Functions | |
void | drive_feedback (int enabled) |
Enables or disables encoder feedback for speed control. | |
void | drive_trim (int enabled) |
Enables or disables drive trim which can be used to compensate for mechanical wheel alignment errors. | |
void | drive_trimSet (int direction, int side, int value) |
Stores trim values to EEPROM. | |
void | drive_trimDisplay (void) |
Display the trim settings. | |
void | drive_displayInterpolation (void) |
Displays the interopolation table stored in EEPROM by the calibration step. For more info, see: http://learn.parallax.com/activitybot/test-and-tune-your-activitybot. | |
void | drive_encoderPins (int encPinLeft, int encPinRight) |
Set encoder pins to values other than the default P14 for left encoder and P15 for right encoder. Stores values in EEPROM, so you only need to call this function at the start of one program. Programs that are after that will get the values from EEPROM. | |
void | drive_servoPins (int servoPinLeft, int servoPinRight) |
Set servo pins to values other than the default P12 for left servo and P13 for right servo. Stores values in EEPROM, so you only need to call this function at the start of one program. Programs that are after that will get the values from EEPROM. | |
void | drive_speed (int left, int right) |
Set wheel speeds in encoder ticks per second. An encoder tick is 1/64th of a revolution, and makes causes the wheel to roll 3.25 mm. | |
void | drive_ramp (int left, int right) |
Ramp up to the specified wheel speeds. It works almost the same as drive_speed, except that it steps up the speed every 50th of a second. The default ramping rate is 4 ticks per 50th of a second. This function will make your program wait while it ramps. | |
void | drive_rampStep (int left, int right) |
This funciton allows your code to ask for a speed repeatedly in a loop, but each time your code asks for that speed, it takes a step toward the speed. This helps cushon sudden maneuvers in sensor navigation, where the conditions might change more rapidly than you would want your ActivityBot's speed to change. | |
void | drive_setRampStep (int stepsize) |
Overrides the default 4 ticks/second per 50th of a second for ramping. | |
void | drive_distance (int left, int right) |
Make the ActivityBot wheels roll certain encoder tick distances. An encoder tick is 1/64th of a wheel turn and makes the wheel roll 3.25 mm. NOT YET IMPLEMENTED, use drive_goto instead. | |
void | drive_close (void) |
Stop the servo/encoder system. This is useful for reclaiming a processor for other tasks. | |
int | drive_open () |
Start or restart the servo/encoder system. | |
void | drive_setMaxSpeed (int speed) |
Modifies the default maxiumum top speed for use with encoders. The default is 128 ticks/second = 2 revolutions per second (RPS). This is the full speed that drive_distance and drive_goto use. This value can currently be reduced, but not increased. Speeds faster than 128 ticks per second are "open loop" meaning the control system does not use the encoders to correct distance/speed. | |
void | drive_goto (int distLeft, int distRight) |
Make each wheel go a particular distance. Recommended for straight forward, backward, turns and pivots. Not recommended for curves. This function ramps up to full speed if the distance is long enough. It holds that speed until it needs to ramp down. After ramping down it applies compensation. This function is primarily a convenience for dead reckoning, and does not return until the maneuver has completed. | |
void | drive_getTicks (int *left, int *right) |
Get the measured number of ticks the have traveled. | |
void | drive_getTicksCalc (int *left, int *right) |
Get the calculated number of ticks the encoders should have traveled. |
This library takes care of encoder monitoring and servo signalling, and provides a simple set of functions for making the ActivityBot go certain distances and speeds.
For more information, go here:
http://learn.parallax.com/activitybot/navigation-basics
Please submit bug reports, suggestions, and improvements to this code to edito. r@pa ralla x.co m
v0.5.5
v0.5.1
To-Do
void drive_distance | ( | int | left, |
int | right | ||
) |
Make the ActivityBot wheels roll certain encoder tick distances. An encoder tick is 1/64th of a wheel turn and makes the wheel roll 3.25 mm. NOT YET IMPLEMENTED, use drive_goto instead.
left | Left wheel encoder tick distance. |
right | Right wheel encoder tick distance. |
void drive_encoderPins | ( | int | encPinLeft, |
int | encPinRight | ||
) |
Set encoder pins to values other than the default P14 for left encoder and P15 for right encoder. Stores values in EEPROM, so you only need to call this function at the start of one program. Programs that are after that will get the values from EEPROM.
encPinLeft | I/O pin number for the left encoder signal connection. |
encPinRight | I/O pin number for the right encoder signal connection. |
void drive_feedback | ( | int | enabled | ) |
Enables or disables encoder feedback for speed control.
enabled | Set to 1 to enable feedback (default) or 0 to disable. |
void drive_getTicks | ( | int * | left, |
int * | right | ||
) |
Get the measured number of ticks the have traveled.
The system samples the encoders at 400 times per second.
*left | Pointer to variable to receive the measured left distance. |
*right | Pointer to variable to receive the measured right distance. |
void drive_getTicksCalc | ( | int * | left, |
int * | right | ||
) |
Get the calculated number of ticks the encoders should have traveled.
Get the calculate number of ticks the encoders should have traveled. Distance is in ticks. The wheel has 64 encoder ticks, each accounting for 3.25 mm of distance.
The system samples the encoders at 400 times per second.
*left | Pointer to variable to receive the calculated left distance. |
*right | Pointer to variable to receive the calculated right distance. |
The system updates the predicted distance 400 times per second, based on the speed the wheels should be going.
*left | Pointer to variable to receive the calcualted left distance. |
*right | Pointer to variable to receive the calcualted right distance. |
void drive_goto | ( | int | distLeft, |
int | distRight | ||
) |
Make each wheel go a particular distance. Recommended for straight forward, backward, turns and pivots. Not recommended for curves. This function ramps up to full speed if the distance is long enough. It holds that speed until it needs to ramp down. After ramping down it applies compensation. This function is primarily a convenience for dead reckoning, and does not return until the maneuver has completed.
distLeft | Left wheel distance. |
distRight | Right wheel distance. |
void drive_ramp | ( | int | left, |
int | right | ||
) |
Ramp up to the specified wheel speeds. It works almost the same as drive_speed, except that it steps up the speed every 50th of a second. The default ramping rate is 4 ticks per 50th of a second. This function will make your program wait while it ramps.
left | Left wheel speed in ticks per second. |
right | Left wheel speed in ticks per second. |
void drive_rampStep | ( | int | left, |
int | right | ||
) |
This funciton allows your code to ask for a speed repeatedly in a loop, but each time your code asks for that speed, it takes a step toward the speed. This helps cushon sudden maneuvers in sensor navigation, where the conditions might change more rapidly than you would want your ActivityBot's speed to change.
left | Left wheel speed in ticks per second. |
right | Left wheel speed in ticks per second. |
void drive_servoPins | ( | int | servoPinLeft, |
int | servoPinRight | ||
) |
Set servo pins to values other than the default P12 for left servo and P13 for right servo. Stores values in EEPROM, so you only need to call this function at the start of one program. Programs that are after that will get the values from EEPROM.
servoPinLeft | I/O pin number for the left servo signal connection. |
servoPinRight | I/O pin number for the right servo signal connection. |
void drive_setMaxSpeed | ( | int | speed | ) |
Modifies the default maxiumum top speed for use with encoders. The default is 128 ticks/second = 2 revolutions per second (RPS). This is the full speed that drive_distance and drive_goto use. This value can currently be reduced, but not increased. Speeds faster than 128 ticks per second are "open loop" meaning the control system does not use the encoders to correct distance/speed.
speed | Maximum cruising speed for drive_distance and drive_goto. |
void drive_setRampStep | ( | int | stepsize | ) |
Overrides the default 4 ticks/second per 50th of a second for ramping.
stepsize | The size of each step in ticks/second to change every 50th of a second |
void drive_speed | ( | int | left, |
int | right | ||
) |
Set wheel speeds in encoder ticks per second. An encoder tick is 1/64th of a revolution, and makes causes the wheel to roll 3.25 mm.
left | Left wheel speed in ticks per second. |
right | Left wheel speed in ticks per second. |
void drive_trim | ( | int | enabled | ) |
Enables or disables drive trim which can be used to compensate for mechanical wheel alignment errors.
enabled | Set to 1 to enable trim (default) or 0 to disable. |
void drive_trimDisplay | ( | void | ) |
Display the trim settings.
Displays most recent direction, side, and value settings from the most recent call to drive_trimSet.
void drive_trimSet | ( | int | direction, |
int | side, | ||
int | value | ||
) |
Stores trim values to EEPROM.
Trim values can compensate for mechanical wheel alignment errors. When you set the ActivityBot's trim, you are telling it to make a certain wheel turn an extra tick per certain number of ticks. For example, you can use this to make the right wheel turn 1 extra tick per every 64 ticks. It will actually just expect to see an encoder transition 1/64th of a tick sooner with every tick.
direction | Selects to set the trim for a given direction. Use AB_FORWARD OR AB_BACKWARD. |
side | Selects the side to make one more or less ticks per number of ticks. Use AB_LEFT or AB_RIGHT to select the left or right wheel. |
value | Number of ticks that should elapse before the extra tick will have accumulated. Use a negative number if you want a given wheel to go one less tick per number of ticks instead of one more tick. |