Robot Calibration

We use the framework released by the group of Giorgio Grisetti for calibrating the pose of the sensors (LIDAR and/or camera) as well as the odometry parameters of the differential drive platform. The repository can be found on gitlab, and the paper here. The following is the general outlook of the calibration process:

  • we give some initial values to the parameters we want to calibrate: e.g. 2D pose of the LIDAR + wheel separation and diameters for the differential drive platform;

  • we let the robot move along some trajectory (ideally an 8-path) and record all the relevant data: the ROS tf transformations for the wheels and the raw laser scanner data;

  • the relative transformations based on the wheel encoders can be computed from the differential drive model, and the relative transformations based on the laser scanner can be computed by using a scan matcher;

  • the calibration framework optimizes all parameters so that the sensor trajectories align.

2D Configuration: LIDAR-Odometry Calibration

In this scenario we calibrate the differential drive parameters as well as the pose of the LIDAR. This will be enough for performing SLAM experiments in 2D as well as autonomous driving of the platform.

Launch the Makeblock-odom-LIDAR desktop shortcut on the robot. On our local computer we will drive the robot using a joystick; for that, launch the following file:

desktop:~$ roslaunch robot_launch remotecontrol.launch

Locally, we will record a bagfile with all the necessary topics for the calibration while the robot is moving around:

desktop:~$ rosbag record tf tf_static scan imu odom  /makeblock/lwheel /makeblock/rwheel /joint_states

Once we are done recording the movement of the robot, we will edit the calibration launch file to point to the bagfile we just recorded, and launch it:

desktop:~$ roscd robot_launch/calibration
desktop:~/ws/src/robot_launch/calibration$ gedit calibration.launch
<?xml version="1.0" encoding="UTF-8"?>
<launch>
	
    <param name="/use_sim_time" value="true"/>

    <param name="robot/name" value="mkROS" />
	<param name="robot_description" textfile="$(find system_setup)/robotmodel.urdf" />

    
    <node pkg="rosbag" type="play" name="player" args="--clock -r 0.7  $(find srrg_nw_calibration_ros)/data/YOUR_FILE.bag"/>
    [...]

The calibration process will display an rviz window with the robot model, the tfs and the laser scans.

Towards the end of it, you will see the result on the terminal window something like this:

[8/10] chi^2: 0.000265108
[9/10] chi^2: 0.000266389
[10/10] chi^2: 0.000265372
P [/base_link -> odom_params]:  0.0312667 -0.0310829   0.153682
P [/odom -> /laser]:  0.000531759 -0.000581597   -0.0315804

The values 0.0312667 and -0.0310829 are the wheel radii in meters (when moving forward, one of the wheel rotates clockwise and the other counterclockwise, thus the opposite signs), and 0.153682 is the calibrated value for the wheel separation. We can convert the calibrated wheel radii to encoder ticks per meter (360 ticks per wheel revolution) and edit the control/odometry launch file accordingly:

up-2022:~$ roscd robot_launch/control
up-2022:~/ws/src/robot_launch/control$ gedit odometry.launch
[...]
    <!-- calibrated values -->
    <arg name="ticks_per_meter" value="1876" />
    <arg name="wheel_separation" value="0.153682" />
    
    <arg name="odom_frame_id" value="odom" />
    <arg name="base_frame_id" value="base_link"/>
	
    <arg name="rate" value="50" />
	<node name="odom_publisher" pkg="diff_drive" type="diff_drive_odometry" output="screen" if="$(arg use_ext_odom_publisher)">
    	
    	<param name="ticks_per_meter" value="$(arg ticks_per_meter)"/>
    	<param name="wheel_separation" value="$(arg wheel_separation)"/>
        <param name="odom_frame_id" value="$(arg odom_frame_id)"/>
        <param name="rate" value="$(arg rate)"/>
        <param name="base_frame_id" value="$(arg base_frame_id)"/>
        
        <remap  from="/lwheel_ticks" to="/makeblock/lwheel"/>
        <remap  from="/rwheel_ticks" to="/makeblock/rwheel"/>
    </node>
</launch>

It is possible that the calibrated wheel radii are not equal for both wheels —for example if the weight of the robot is not well balanced, the robot will tend to deviate from a straight motion. In that case we would rely on our own node for the wheel odometry, since the ROS differential drive node only takes one ticks per meter parameter.

3D Configuration

In this configuration we calibrate the poses of the Depth camera and LIDAR sensors, together with the odometry parameters.

Last updated