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

Null Chain Kinect URDF Calibration

Description: Calibrate the Kinect sensor that is not part of any calibration chain into PR2's URDF (practically for every mount point but head).

Tutorial Level: INTERMEDIATE

nullchain_kinect_calibration_resized.JPG

This tutorial will teach you how to calibrate the Kinect sensor that is not part of any calibration chain (so called null chain) into PR2's URDF. Practically this holds for Kinects mounted on e.g. PR2's chest, shoulders, etc. This calibration process makes use of stock PR2 calibration and is based on estimating the Kinect's RGB camera pose within the URDF model. The instructions below assume that torso_lift_link is being used as a parent frame of the to-be calibrated sensor. Please modify if this is not your case (e.g. mount on a base).

Steps to re-produce the calibration:

Checkout pr2_calibration Stack:

hg clone https://kforge.ros.org/calibration/pr2_calibration

Switch to diamondback-nullchain-kinect branch

Switch to diamondback-nullchain-kinect branch in order to get the configuration files and enable samples for Kinect sensor. Inside repository run:

hg up -C diamondback-nullchain-kinect

Please make sure that from now everything is being ran on diamondback-nullchain-kinect branch!!!

User-needed Modifications

This part gets a bit tricky as we will be using the sample configurations from the stock calibration code and we thus have to first find out in which configurations the checkerboards are visible.

Finding Valid Configurations

First enable the sensor for all configuration files by adding the

- {cam_id: kinect_torso, config: small_cb_7x6}

to all far samples and

- {cam_id: kinect_torso, config: small_cb_4x5}

to all left and right samples.

Secondly, in

pr2_calibration_launch/capture_data/capture_exec_pr2.launch

switch from

pr2_exec.py to pr2_sample_chooser.py.

Run

ssh prx -X
sudo robot start
roslaunch pr2_calibration_launch capture_data.launch

This will give you an interactive shell to select either Far (F), Left (L) or Right (R) sample. It will also ask you about the sample number (options are 0 for far and 0-31 for either left or right) and the timeout. You can use 2 seconds for all but samples that include tilt_laser. Go through all the samples (tedious I know) and note down which samples were visible in kinect_torso window and successfully captured.

After you finished going through all the samples Ctrl+C the capturing and disable kinect_torso for ALL failed samples.

Compile

Prepend path to pr2_calibration stack to ROS_PACKAGE_PATH and rosmake it.

Modify Uncalibrated URDF

Before you start calibrating the robot, the robot should be started from the newest urdf file that is available. In the '/etc/ros/diamondback/urdf' folder (there is a specific folder for each distro), you find a number of urdf files called 'robot_uncalibrated_x.x.x.xml'. Modify the newest uncalibrated urdf file (as root) by inserting the following block into it:

   1 <joint name="kinect_torso_rgb_frame_joint" type="fixed">
   2     <origin rpy="-1.57 0.0 0.0" xyz="0.04 0.0 -0.25"/>
   3     <parent link="torso_lift_link"/>
   4     <child link="kinect_torso_rgb_frame"/>
   5   </joint>
   6   <link name="kinect_torso_rgb_frame">
   7     <inertial>
   8       <mass value="0.01"/>
   9       <origin xyz="0 0 0"/>
  10       <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
  11     </inertial>
  12     <visual>
  13       <origin rpy="0 0 0" xyz="0 0 0"/>
  14       <geometry>
  15         <box size="0.01 0.01 0.01"/>
  16       </geometry>
  17     </visual>
  18   </link>
  19   <joint name="kinect_torso_rgb_optical_frame_joint" type="fixed">
  20     <origin rpy="-1.5707963268 -0.0000000000 -1.5707963268" xyz="0.0000000000 0.0000000000 0.0000000000"/>
  21     <parent link="kinect_torso_rgb_frame"/>
  22     <child link="kinect_torso_rgb_optical_frame"/>
  23   </joint>
  24   <link name="kinect_torso_rgb_optical_frame"/>

This step is necessary because pr2_calibration stack cannot generate a URDF from scratch. It takes an existing URDF and modifies a specific number in it.

Important Please note that the transform between the kinect_torso_rgb_frame and the torso_lift_link frame has to be as closely approximated to the real one as possible in order for the estimation step to generate valid results. One way to obtain a rather accurate position approximation is to launch the mannequin mode controller, bring the gripper_tool_frame next to the optical center of the Kinect sensor and run:

rosrun tf tf_echo parent_frame and [r|l]_gripper_tool

Start Up Kinect sensor

Install openni_camera package and make it. Comment the following line in the openni_camera/launch/openni_node.launch file:

  <!--<include file="$(find openni_camera)/launch/kinect_frames.launch"/>-->

Replace following 2 lines in openni_camera/launch/openni_node.launch file:

   1   <param name="rgb_frame_id" value="/openni_rgb_optical_frame" />
   2   <param name="depth_frame_id" value="/openni_depth_optical_frame" />

with following 2:

  <param name="rgb_frame_id" value="/kinect_torso_rgb_optical_frame" />
  <param name="depth_frame_id" value="/kinect_torso_depth_optical_frame" />

Note that the frame names can be arbitrary but they have to match the ones from the above section of URDF file.

Start up Kinect:

roslaunch openni_camera openni_node.launch

PR2 Full System Calibration

Perform PR2 Full System Calibration:

(http://www.ros.org/wiki/pr2_calibration/Tutorials/Calibrating%20the%20PR2).

If intrinsic calibration is still satisfactory it is safe to skip step 2: http://www.ros.org/wiki/pr2_calibration/Tutorials/Calibrating%20the%20PR2#Calibrate_Camera_Intrinsics.

Note that you will in fact now have 9 image_view windows with an additional kinect_torso window.

Wiki: pr2_calibration/Tutorials/NullChainKinectURDFCalibration (last edited 2011-05-27 04:58:44 by MichaelFerguson)