The DPRG Outdoor Challenges: Simple Navigation Calibration and Tuning

David P. Anderson


Howdy,

The robot location calculation for a differential drive platform that we are calling "odometry" requires three constants to specify the robot's physical geometry and encoding. These are:
1. Encoder counts per linear inch: COUNTS_PER_INCH

2. Distance between drive wheels: WHEEL_BASE

3. Difference in wheel size: WHEEL_SIZE_ERROR

These constants are needed for the "Basic Odometry" function defined in the previous posting on robot navigation math routines:

http://geology.heroy.smu.edu/~dpa-www/robo/challenge/math.html

Of course inches can be meters or whatever metric you prefer. This example uses inches. These constants must be measured by the robot itself rather than calculated from its geometry. By tuning these three numbers the odometry accuracy can be substantially improved.

In the past I've pointed folks interested in knowing how to tune their robot's odometry to two papers from The University of Michigan's J.Borenstein. The first, "Where Am I?" covers a wide range of topics in robot localization, including a chapter, 5, on correcting errors in odometry:

http://www.eng.yale.edu/ee-labs/morse/other/intro.html

The second is really a companion to the first and describes the University of Michigan Bench Mark, (UMBMark), a technique for identifying certain types of odometry errors:

http://www-personal.umich.edu/~johannb/Papers/umbmark.pdf

I seriously encourage all robot builders to have both of these papers in their robot reference library.

However, having said that, I have also observed a lot of folks' eyes glaze over when they see all the math involved in these two documents.

So here is my attempt at a quick and dirty description of how to tune your robot's odometry calculations using these methods with a minimum of math.

1. Counts per inch.

This is the simplest constant to measure and must be done first. Set the robot down on the floor and have it drive a straight line as well as possible, and manually stop it when it reaches 10 feet, while counting the total number of encoder counts for each wheel.

If you have an LCD or similar display on the robot you can print the accumulated counts on the display, or send them over a telemetry link, or just download them over a serial port at the end of the run.

Then encoder counts_per_inch is just the average of the left and right counts divided by 120 inches (i.e., 10 feet):

COUNTS_PER_INCH = ((left_counts + right_counts)/2)/120;

Many institutional buildings have handy 1 foot square tiles in the hallways, which makes a convenient measuring tape for this procedure.

2. Wheel base

Measure with a ruler the distance between the center of the two drive wheels as the starting value for WHEEL_BASE, and plug that value into the odometry calculations. Now have the robot drive around a large square while tracking its location, and measure how close it returns to the origin. This is the UMBMark, though there is more to it.

For first order corrections use the following rules:
a. If the robot does not make it back to the origin,
WHEEL_BASE is TOO SMALL
Make it a tiny bit larger and run the square again.

b. If the robot overshoots the origin, then
WHEEL_BASE is TOO LARGE.
Make it a tiny bit smaller and run the square again.
Run these calibration procedures both clockwise and counter-clockwise and adjust the WHEEL_BASE constant for to reduce the error and center the error cluster over the origin waypoint. This may take several iterations.

3. Wheel size error

Wheel size error means that the two wheels are not exactly the same size, and when the robot thinks it is driving straight it's actually driving a curve. In my experience this is a secondary effect, so the wheel base value should be determined with as much accuracy as possible first, and then the wheel size error determined (probably followed by a final tweak of the wheel base).

The clever way the UMBMark is able to separate out these two errors has to do with symmetry of clockwise and counter-clockwise squares. The robot must run tests in both directions.

For wheel base errors, the patterns will by mirrored symmetrically left and right, "butterfly" fashion. If the robot arrives 3 feet short of the origin coming from the right in a clockwise pattern, it will also arrive 3 feet short of the origin coming from the left in a counter-clockwise pattern. The ending position will be bilaterally symmetrical, like a butterfly.

For wheel size errors, however, the errors will not be symmetrical.

For example, a robot curving slightly to the left on a clockwise pattern will arrive short of the goal, but on a counter-clockwise pattern will overshoot the goal.

The method for correcting this is to have two COUNTS_PER_INCH constants, one for each wheel. These are arrived at by adding the WHEEL_SIZE_ERROR constant to COUNTS_PER_INCH for one wheel, and subtracting it from COUNTS_PER_INCH for the other wheel:
LEFT_COUNTS_PER_INCH = COUNTS_PER_INCH + WHEEL_SIZE_ERROR;
RIGHT_COUNTS_PER_INCH = COUNTS_PER_INCH - WHEEL_SIZE_ERROR;

so that the average counts per inch determined in the first step remains the same. Again, make tiny adjustments to the WHEEL_SIZE_ERROR and run the patterns again to reduce the odometry errors caused by differeing wheel size.

By way of example, the geometry for my SR04 robot, a two-wheel differential drive robot with castering tail wheel, is:

#define WHEEL_BASE 9.73
#define CLICKS_PER_INCH 79.50
#define WHEEL_SIZE_ERROR .02
#define LEFT_CLICKS_PER_INCH (CLICKS_PER_INCH + WHEEL_SIZE_ERROR)
#define RIGHT_CLICKS_PER_INCH (CLICKS_PER_INCH - WHEEL_SIZE_ERROR)


4. Calibration runs.

Of course the WHEEL_BASE and WHEEL_SIZE errors will be mixed in together along with random errors caused by the variations in the floor and the robot's path along the pattern. Borenstein suggests that you run the pattern five times clockwise and average the final locations to remove the random "noise," and then do the same for the counter-clockwise pattern.

For those who might have sighted in a rifle scope, this is a familiar procedure. Fire five shots and measure the spread and offset of the pattern. You'd like that pattern centered over the bull's eye, which is the origin location in our case. You can't do much about the spread, except become a better shot. In our case that probably means improving the mechanical precision of the robot platform.

Note that a lot of the effort here is to accurately define the values that will be used to determine the robot's heading, the "theta" of our odometry calculations. If theta is determined from something other than the wheel encoders (like a compass or IMU) then another whole set of calibration procedures must be used, which will have to be the subject of another post.

Hope this is useful.

happy roboting!
dpa



PREV NEXT



Rev 1.1
Copyright (c) 2008 David P. Anderson. Verbatim copying and distribution of this entire article are permitted worldwide, without royalty, in any medium, provided this notice is preserved.