(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Create Odometry and Gyro Calibration

Description: /!\ This is only necessary if you have a Create base. The Kobuki comes with a factory calibrated gyro. This will show you how to calibrate or test the calibration of a TurtleBot which is highly recommended when running any navigation based application.

Tutorial Level: BEGINNER

Setup

Note: Determine which gyro your TurtleBot is using, TurtleBots made by different manufacturers have gyros with different measurement rates. You will need to look at the small chip on the right side of the turtlebot power/sensor board and find its part number (example). Some common ones are:

Chip

Setting

ADXRS613

150

ADXRS652

250

This link may help: http://www.alldatasheet.com/view.jsp?Searchword=ADXRS6

Set the gyro_measurement_range value before you run calibration by using rqt_reconfigure or editing the configuration file as explained in the results section below.

First position TurtleBot at the center of a long straight wall (at least 2 meters long), facing towards the wall, at about 30 cm away from the wall.

  • calibration1.JPG calibration2.JPG

Execution

This assumes you have already started the robot

Now ssh (ssh help) into the TurtleBot and run the calibration routine:

  • To ssh in to a TurtleBot from a workstation computer:

    • determine the IP_OF_TURTLEBOT by using ifconfig (Need more help)

      To determine a computer's IP address and network interface in linux:

      • ifconfig

      You will see something like:

      • lo        Link encap:Local Loopback  
                  inet addr:127.0.0.1  Mask:255.0.0.0
                  inet6 addr: ::1/128 Scope:Host
                  UP LOOPBACK RUNNING  MTU:16436  Metric:1
                  RX packets:6658055 errors:0 dropped:0 overruns:0 frame:0
                  TX packets:6658055 errors:0 dropped:0 overruns:0 carrier:0
                  collisions:0 txqueuelen:0 
                  RX bytes:587372914 (587.3 MB)  TX bytes:587372914 (587.3 MB)
        
        wlan1     Link encap:Ethernet  HWaddr 48:5d:60:75:58:90  
                  inet addr:10.0.129.17  Bcast:10.0.129.255  Mask:255.255.254.0
                  inet6 addr: fe80::4a5d:60ff:fe75:5890/64 Scope:Link
                  UP BROADCAST RUNNING MULTICAST  MTU:1500  Metric:1
                  RX packets:101983 errors:0 dropped:0 overruns:0 frame:0
                  TX packets:37244 errors:0 dropped:0 overruns:0 carrier:0
                  collisions:0 txqueuelen:1000 
                  RX bytes:49326141 (49.3 MB)  TX bytes:7588044 (7.5 MB)
      • the network interface for the wireless card is wlan1

      • the IP address of the computer is 10.0.129.17


    • use ssh to connect to the TurtleBot

      ssh turtlebot@IP_OF_TURTLEBOT

roslaunch turtlebot_calibration calibrate.launch

Turtlebot will perform a number of calibration spins. According to this note from Tully Foote, the calibration routine should turn 720° the first time then 360° the following times. Each "time" referred to here is one execution of the calibration routine, where each routine begins with "Aligning base with wall" and ends with IMU and odom error output. The full calibrate.launch task contains 4 such routines (to gain a better understanding of what exactly is supposed to happen during calibration, you can read the source code at <ROS_ROOT>/lib/turtlebot_calibration/calibrate.py).

When it finishes, you'll see a print on the screen like this (and I'm not yet sure if you should expect similar numbers or not):

  • [INFO] [WallTime: 1299286750.821002] Multiply the 'turtlebot_node/gyro_scale_correction' parameter with 1.002262
    [INFO] [WallTime: 1299286750.822427] Multiply the 'turtlebot_node/odom_angular_scale_correction' parameter with 1.000263
  • If the TurtleBot does not successfully return to facing the wall before executing the next rotation the data will be incorrect. This can be caused by too big of an error in the existing parameters. If it under rotates, increase the odom parameter and retry. If it over rotates, lower the odom_parameter and retry.

  • Alternatively, you can try adjusting the gyro parameter as suggested in this post. Since there is no description here of exactly what the calibration routine is doing, I don't know what is the correct way to address these kinds of issues.

Results

The calibration routine will output 2 numbers. The correction for the gyro and the correction for the odometry. The values are factors to multiply with the current parameters to get the best results (see also this QA and this QA).

After running the calibration set the parameters to the old value multiplied by the correction.

The two parameters are:

  • turtlebot_node/gyro_scale_correction
  • turtlebot_node/odom_angular_scale_correction

For a single run you can set the parameters using dynamic_reconfigure:

rosrun rqt_reconfigure rqt_reconfigure

Then select the turtlebot_node and set the parameters. You must use Dynamic Reconfigure or else turtlebot_node will not pick up the changes. Using rosparam set is not enough. (You could also restart turtlebot_node after each calibration, but this requires changing the parameters in the bringup launch file.)

Return to the calibration step and repeat the process until both multipliers are close to 1. If calibration is not working correctly, then the numbers may never converge. It is hard to say whether the process is diverging or not, because I've not seen anyone give any guidelines as to what are reasonable values to expect for these parameters. If the process starts driving your gyro correction to 0 you should probably suspect that something is wrong.

Once both correction parameters have converged to stable values, add the following with the values you received to the turtlebot_bringup/minimal.launch file to use these parameters in the future(See http://answers.ros.org/question/217629/calibrating-turtlebotcreate-can-not-find-turtlebotlaunch/):

<param name="turtlebot_node/odom_angular_scale_correction"> value="some numerical value that you got"/>
<param name="turtlebot_node/gyro_scale_correction"> value="some numerical value that you got"/>

What Next?

Visualisation or return to the TurtleBot main page.

Wiki: turtlebot_calibration/Tutorials/Calibrate Odometry and Gyro (last edited 2017-03-25 17:58:57 by LukasSeveringhaus)