(!) 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.

Force-torque sensor calibration

Description: This tutorial shows you how to use the force_torque_sensor_calib package to calibrate your force-torque sensor. It calibrates the bias of the sensor as well as the mass and the center of mass of the gripper attached to the force-torque sensor.

Keywords: calibration, force sensor, sensor calibration, f/t sensor, force, torque

Tutorial Level: BEGINNER

Overview and prerequisites

The software calibrates the F/T sensor by moving the manipulator into a number of different poses and using the resulting F/T sensor and accelerometer signals for computing a least-squares estimate of the parameters. It thus assumes that you have an accelerometer/imu whose reference frame is already calibrated with respect to some reference frame on the robot manipulator, e.g. the base frame. It also assumes that your robot arm can be controlled using MoveIt!. It also assumes that you have already calibrated the calibration matrix of the F/T sensor (this matrix is tipically given by the manufacturer).

The (uncalibrated) force-torque sensor should publish geometry_msgs/WrenchStamped messages while the accelerometer should publish sensor_msgs/Imu messages.

To run the force-torque sensor calibration node for your own robot you need to modify the example_ft_calib_params.yaml configuration file and the example_ft_calib.launch launch file contained in the config and launch folders of the force_torque_sensor_calib package.

The calibration software will output a .yaml calibration file which by default will be stored in the ~/.ros/ft_calib folder.

Setting up the calibration node parameters

Copying the example calibration node parameter file

In order to calibrate the force-torque sensor you need to provide a set of parameters to the calibration node. The easiest way to do this is to use the example_ft_calib_params.yaml YAML file provided in the config folder of the force_torque_sensor_calib package.

You can copy this configuration file to your own force-torque sensor calibration package for your robot:

roscp force_torque_sensor_calib example_ft_calib_params.yaml <your_package_directory>/config

The configuration file looks like this:

# main loop frequency [Hz] (should be as fast as F/T sensor publish frequency)
loop_rate: 650.0

# waiting time after moving to each pose before taking F/T measurements
wait_time: 4.0

# Name of the moveit group
moveit_group_name: 'left_arm'

# Name of the calib file
calib_file_name: 'ft_calib_data.yaml'

# Name of the directory
calib_file_dir: '~/.ros/ft_calib'

# Name of file to store measurements
meas_file_name: 'ft_calib_meas.txt'

# Name of the directory
meas_file_dir: '~/.ros/ft_calib'

# don't execute random poses
random_poses: false

# number of random poses
number_random_poses: 0

# the poses to which to move the arm in order to calibrate the F/T sensor
# format: [x y z r p y]  in meters, radians
# poses_frame_id sets the frame at which the poses are expressed
poses_frame_id: 'arm_base_link'

pose0: [-0.486, 0.367, -0.000, 1.571, 1.571, 3.130]
pose1: [-0.486, 0.367, -0.000, 1.571, 0.8, 3.140]
pose2: [-0.486, 0.367, -0.000, 1.571, 0.4, 3.140]
...

Editing the calibration node parameter file

  1. First you need to specify the rate (in Hz) at which the main loop of the calibration node will run (you can set it equal to the publishing frequency of your force-torque sensor):

    # main loop frequency [Hz] (should be as fast as F/T sensor publish frequency)
    loop_rate: 650.0
  2. Set the waiting time (in sec) between the moment the manipulator reaches each pose and the calibration node starts taking force-torque measurements. This is in case your arm vibrates slightly when it finishes executing a trajectory, to avoid erroneous force-torque measurements affecting the calibration procedure

    # waiting time after moving to each pose before taking F/T measurements
    wait_time: 4.0
  3. Specify the moveit group name of the robot arm to which the force-torque sensor is attached to.

    # Name of the moveit group
    moveit_group_name: 'left_arm'
  4. Set the file name and directory for saving the calibration data. By default the output calibration data is saved in the ~/.ros/ft_calib folder.

    # Name of the calib file
    calib_file_name: 'ft_calib_data.yaml'
    
    # Name of the directory
    calib_file_dir: '~/.ros/ft_calib'
  5. Set the file name and directory for saving the measurements used by the calibration node to estimate the F/T sensor parameters. You can later use these measurements to reestimate offline the F/T sensor parameters yourself. By default the measurements are saved in the ~/.ros/ft_calib folder

    # Name of file to store measurements
    meas_file_name: 'ft_calib_meas.txt'
    
    # Name of the directory
    meas_file_dir: '~/.ros/ft_calib'
  6. Set the poses your robot arm will move to. Here you have two options:

    • Random poses: you can make your robot arm move to random poses and just specify how many poses you want to use for calibration:

      # execute random poses
      random_poses: true
      
      # number of random poses
      number_random_poses: 30
      This is the easiest way to set up the calibration software. 30 or more poses are recommended but you should be careful that the poses have a significant spread in orientation in order to get a good calibration.
    • Manually configured poses: if you choose to manually set the poses for calibration yourself, you can do so by specifying any number of poses through the pose0, pose1, pose2, ..., poseN parameters. You can specify as many poses as you want, 30 or more are recommended. Make sure that you have a significant spread in the orientation of the poses to get good calibration results. Remember to set the random_poses parameter to false and also to set the frame ID in which the poses are expressed through the poses_frame_id parameter:

      # Name of file to store measurements
      meas_file_name: 'ft_calib_meas.txt'
      
      # Name of the directory
      meas_file_dir: '~/.ros/ft_calib'
      
      # don't execute random poses
      random_poses: false
      
      # number of random poses
      number_random_poses: 0
      
      # the poses to which to move the arm in order to calibrate the F/T sensor
      # format: [x y z r p y]  in meters, radians
      # poses_frame_id sets the frame at which the poses are expressed
      poses_frame_id: 'arm_base_link'

Setting up the launch file

You can copy and edit the example_ft_calib.launch file:

<?xml version="1.0"?>
<launch>

  <node name="ft_calib" pkg="force_torque_sensor_calib" type="ft_calib_node" cwd="node" respawn="false" output="screen" >
    <rosparam command="load" file="$(find force_torque_sensor_calib)/config/example_ft_calib_params.yaml"/>
    <remap from="/ft_calib/ft_raw" to="/ft_sensor/ft_raw"/>
    <remap from="/ft_calib/imu" to="/imu/data" />
  </node>
</launch>

1. Set the location of the configuration file you edited in the previous step:

    <rosparam command="load" file="$(find force_torque_sensor_calib)/config/example_ft_calib_params.yaml"/>

2. Remap the topic subscriptions for the (uncalibrated) F/T sensor and accelerometer (IMU):

    <remap from="/ft_calib/ft_raw" to="/ft_sensor/ft_raw"/>
    <remap from="/ft_calib/imu" to="/imu/data" />

Running the calibration node

Make sure that there are no objects obstructing the trajectories of the robot arm so that it doesn't collide during the calibration procedure. Launch using the launch file you created, e.g.:

roslaunch force_torque_sensor_calib example_ft_calib.launch

Example calibration file

An example calibration file output from this calibration node can be found under config/ft_calib_data_example.yaml in the force_torque_sensor_calib package.

Wiki: force_torque_tools/Tutorials/Force-torque sensor calibration (last edited 2014-07-31 12:14:25 by FranciscoVina)