DPRG
DPRG List  



[DPRG] Odometry calibration

Subject: [DPRG] Odometry calibration
From: sheila doyle srdoyle at earthlink.net
Date: Mon Jun 9 14:41:00 CDT 2003

Gosh.  I do almost the same system, iterating to the right value.  Except only checking my one wheel encoder (no step 2), watch the bot to iterate to the right answer and doing fewer turns in the corner test.  
Probably not as accurate but does get very close. 

Sheila

-------Original Message-------
>From: "David P. Anderson" <dpa at io.isem.smu.edu>
Sent: 06/09/03 02:07 PM
To: dprglist at dprg.org
Subject: [DPRG] Odometry calibration

> 
> Howdy

Setting up wheel encoders for odometry requires a method of
calibrating them and determining the robot's geometry.  Here's
the method I've used:

1.  First it's necessary to determine as precisely as possible
the number of encoder counts per inch (or whatever your favorite
distance metric).  This number will probably be a fraction and
best expressed in floating point.  (Mark Castelluccio of MRM
board fame defines everything in "microinches" to avoid floating
point.   That might be necessary for some robots).

This step is the easiest and least sensitive.  I adjust the PWM
values for each motor such the the robot drives in a more-or-less
straight line, and print the accumulated encoder counts on the
robot's LCD.  If you don't have an LCD, you'll have to collect the
values and dump them to a terminal later.

Point the robot straight down a hallway and let it drive for a
defined distance.  I use the 1 foot square tiles common in 
institutional buildings, but a simple tape measure will probably
do.  I count something like 10 or 20 or 50 or 100 tiles and then
stop the robot manually, recording the accumulated encoder
counts in my little notebook.

Encoder_counts_per_inch = 
   	(left_encoder + right_encoder)/2)/inches_traveled

where left_encoder and right_encoder are the accumulated encoder
counts and inches_traveled is the number of tiles times 12.

The wheels are almost never the exact same size, but that is
very much a second or third order effect, and it will be dealt
with when the odometry is refined.

2. Next it is necessary to determined the robot's wheel base, i.e.,
the distance between the two differential drive wheels.  

   	a. Measure the distance with a ruler as a starting place.

   	b. Using that measurement, print the calculated robot
   	heading on the LCD (or store for later retrieval).

   	c. Set the motor PWM values forward for one wheel and
   	backward for the other such that the robot will spin
   	slowly in place around the midway point of the axle.

   	d. Now rotate the robot clockwise 10 times and stop it
   	manually exactly as it returns to the starting point,
   	and record the calculated heading.

   	e. Do the same thing counter-clockwise.

   	f.  Adjust the wheel_base value up if the calculated
   	heading is too large, and down if it is too small.

   	g. Loop back to step b and repeat the procedure until
   	you are happy with the accuracy of the calculated heading.
   	

3. Now run the Univ. of Mich. BMark test, clockwise and counter-clockwise.

   	a. This is just four sides of a square, as large as you can practically
   	manage, while printing the calculated position of the robot in X and
   	Y and its orientation in Theta.  

   	b. Measure the error in X and Y of the position that the robot 
   	returns, and record that along with the calculated position,
   	i.e., where the robot thinks it has returned.  The error is
   	the difference between the two.

   	c.  Do the above 5 times clockwise and 5 times counter-clockwise,
   	and average the errors.

   	d.  These numbers are used to do fine corrections of the
   	wheel-base errors and determine inaccuracies in the wheel sizes.
   	

Here's how to interpret the numbers.  If the errors are symmetrical for
clockwise and counter-clockwise runs, the robot is turning too far or
not far enough for a given angle.  The wheel-base values need to
be refined.  If the errors are not symmetrical, the robot is driving
in arcs when it thinks it is driving in straight lines.  The wheel sizes
(clicks per inch) need to be refined.  Do the latter by adding a small
offset to one wheel and subtracting the same offset from the other wheel.
That way the initial clicks per inch value does not have to be adjusted.

Inevitably the errors are a combination of both of these errors.  Try to
reduce the wheel-base error as much as possible first, then go after the
wheel size errors.

I'll try to demo all this at the RBNO.

Borenstein suggest that a robot outfitted with sonar could probably be
setup to run a self-calibrating pattern using the BMark and measuring
and correcting it's own errors.

cheers,
dpa


_______________________________________________
DPRGlist mailing list
DPRGlist at dprg.org
http://nimon.ncc.com/mailman/listinfo/dprglist
> 

More information about the DPRG mailing list