Khepera III Toolbox/Examples/odometry calibration

In this tutorial, you will learn how to calibrate the odometry of your robot. There are various ways to calibrate the odometry of a differential-drive robot. The procedure we show here is perhaps not the most precise, but certainly one of the simplest to quickly get decent calibration values.

Odometry in a Nutshell

edit

Your Khepera III robot is equipped with two DC motors with an encoder each. These encoders allow to obtain the current position of the robot in very small increments (~ 2760 steps for one tour of the wheel). By recording how the wheels turn, it is possible to estimate the trajectory of the robot. This procedure is commonly termed odometry (or position estimation with odometry), and implemented in the program odometry_track.

The major problem of this procedure is error accumulation. At each step (each time you take an encoder measurement), the position update will involve some error. This error accumulates over time and therefore renders accurate tracking over large distances (> 10 m) impossible. Over short distances (< 1 m on a flat surface), however, the odometry can provide extremely precise results.

To get these good results, it is crucial to calibrate the robot. Tiny differences (~ 1 micrometer) in wheel diameter will result in important errors after a few meters, if they are not properly taken into account. Note that each robot (if you have several of them) has to be calibrated individually, preferably on the same type of floor it is being used later on.

Setup

edit

Boot a Khepera III robot and make sure it is connected to your computer via WLAN. In the following text, we assume that you are working with robot 203.

You will need a couple of motor programs and the odometry_goto program for the calibration. Copy these onto your robot with

cd Programs
k3put +203 motor* odometry_goto

Log onto the robot (k3go +203) and initialize the motors:

cd your_username
./motors_initialize

You are now ready to calibrate the odometry of your robot.

Odometry Calibration

edit

There are 3 free parameters in a differential-drive system which have to be known to estimate the position using odometry:

  • The distance per increment (conversion factor) for the left wheel.
  • The distance per increments (conversion factor) for the right wheel.
  • The distance between the two wheels (axis length).

As these parameters are difficult to measure directly, we will instead measure 4 parameters which allow us to derive the parameters above. These 4 parameters, in the order we measure them, are:

  1. increments_per_tour: The number of increments per wheel tour.
  2. axis_wheel_ratio: The ratio between the axis length and the mean wheel diameter.
  3. diameter_left and diameter_right: The two wheel diameters, up to a scaling factor. (Actually, the ratio between the two wheel diameters - this is why these two values count as only one parameter.)
  4. scaling_factor: A scaling factor.

The necessary parameters can then be derived as follows:

distance_per_increment_left = wheel_diameter_left * scaling_factor * 2 * PI / increments_per_tour
distance_per_increment_right = wheel_diameter_right * scaling_factor * 2 * PI / increments_per_tour
axis_length = axis_wheel_ratio * (wheel_diameter_left + wheel_diameter_right) / 2 * scaling_factor

These equations are implemented in calibration.pl, which will create a calibration file and upload it on a robot.

Step 1: Increments per Wheel Tour

edit

The number of increments per wheel tour is a constant, depending only on the encoder and the gearbox used. For the Khepera III robot, this value is 2764.8 (4 * 16 * 1.6 * 27).

You can experimentally verify this number by marking the wheels at one point, and let them move by this number of steps:

./motor_setposition 0 0
./motor_gotoposition 2765 2765

Your marker should be back at exactly the same position.

Step 2: Ratio between Axis Length and Wheel Diameter

edit

Both axis length and wheel diameter can only be measured approximately with standard measurement tools. However, their ratio can be measured very precisely by letting the robot turn on the spot and counting the number of steps. This number divided by 2764.8 directly yields the ratio we are looking for. Of course, to get a more precise value, we will let the robot make several rotations.

From rough measurements with a ruler we know that this ratio is about 2.11 (88.5 mm / 42 mm), so let's start with this value and let the robot turn 10 times on the spot. The position value for that would be:

10 * 2.11 * 2764.8 = 58337.28

Put the robot on the ground, mark its orientation, and type:

./motor_setposition 0 0
./motor_gotoposition -p 58337 -58337

The -p option will enable the trapezoidal speed profile. Once the robot has stopped, it should have almost the same orientation as in the beginning, but is likely to be a few degrees off. Play with the position value until it has exactly the same orientation (as far as you can judge visually). Once you've found a good value (assume it was 58255), just do the math backwards to find out the ratio:

58255 / (10 * 2764.8) = 2.1070

If you want to get a more precise value, you can repeat the above experiments with 100 turns.

Step 3: Wheel Diameters

edit

To experimentally find out diameter differences between the two wheels, we will load our current odometry model onto the robot and then let it move around in your arena while keeping track of its position. At the end, we let the robot move back to where it thinks it started, and note the offset with the real initial position.

To to start with, we need to upload the current odometry values. Edit calibration.pl and execute it:

./calibration.pl

If you set a robot IP address inside this script, it will upload the odometry values onto the robot. (Note that any existing odometry values there will be overwritten without merci.) Otherwise, you have to edit the file /etc/khepera/odometry on the robot by yourself.

The odometry_goto program which you uploaded at the beginning will now use these values to keep track of the position. Put the robot in an open area with at least 1 m space around it, mark its position and type:

./odometry_goto position 1 0 1 1 0 1 0 0

The robot will now move to all corner points of a square with 1 m width, and hence cover a distance of about 4 m. At the end, the robot believes being back at the initial position (with a different heading, though), but is most likely up to 30 cm off. Compare the final position with the initial position (disregard the heading), and ajust the wheel diameter difference as follows:

  • If the robot is on the right of its initial position (i.e. the square is not closed), increase the diameter of the right wheel by increasing the wheel_diameter_difference in calibration.pl.
  • If the robot is on the left of its initial position, increase the diameter of the left wheel by decreasing the wheel_diameter_difference in calibration.pl.

Then, upload the new odometry values and repeat this step until the distance between the initial and final position is less than 5 cm. If you have enough space, you can increase the size of the rectangle to get more precise measurements.

Step 4: Scaling Factor

edit

The scaling factor is again very easy to find out. Put the robot on your floor, which an open area of 1 m in front of it, mark its initial position and type:

./odometry_goto position 1 0

The robot will stop approximately 1 m in front of its initial position. Measure that distance precisely with a measuring tape, and calculate the corresponding scaling factor as follows:

scaling_factor = real_distance / 1 m

You can of course choose a longer distance if you have enough space.

Adjust the scaling factor in calibration.pl, and execute that script again to upload the newest odometry calibration values onto the robot. Your robot is now calibrated!