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

Kinect URDF Calibration (Experimental)

Description: Calibrate the Kinect Sensor into PR2's URDF

Tutorial Level: INTERMEDIATE

kinect_calibration.png

This tutorial will teach you how to calibrate the Kinect sensor into PR2's URDF. This calibration process makes use of stock P2R calibration and is based on estimating the Kinect's RGB camera pose within the URDF model. Coordinate frames for the depth camera are added manually from the openni_camera package (openni_camera/launch/kinect_frames.launch).

Note: For the ROS Electric release, these steps are experimental. Follow this tutorial at your own risk.

Steps to re-produce the calibration:

Checkout pr2_calibration stack:

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

Switch to diamondback-kinect branch

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

hg up -C diamondback-kinect

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

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 (Select ONLY ONE of below options):


Manually

   <joint name="openni_rgb_frame_joint" type="fixed">
    <origin rpy="0.0074253744 0.0418016634 -0.0065419807" xyz="0.0440562178 -0.0135760086 0.1129906398"/>
    <parent link="head_plate_frame"/>
    <child link="openni_rgb_frame"/>
  </joint>
  <link name="openni_rgb_frame">
    <inertial>
      <mass value="0.01"/>
      <origin xyz="0 0 0"/>
      <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
    </inertial>
    <visual>
      <origin rpy="0 0 0" xyz="0 0 0"/>
      <geometry>
        <box size="0.01 0.01 0.01"/>
      </geometry>
    </visual>
  </link>
  <joint name="openni_rgb_optical_frame_joint" type="fixed">
    <origin rpy="-1.5707963268 -0.0000000000 -1.5707963268" xyz="0.0000000000 0.0000000000 0.0000000000"/>
    <parent link="openni_rgb_frame"/>
    <child link="openni_rgb_optical_frame"/>
  </joint>
  <link name="openni_rgb_optical_frame"/>

Using a Script

Download following script: http://code.in.tum.de/indefero/index.php//p/mapping/source/tree/master/pcl_cloud_tools/scripts/insert_kinect_urdf.py and run:

python  insert_kinect_urdf.py <robot_uncalibrated_x.x.x.xml>


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. See an attached robot.xml for where exactly to make an insertion. Please note that the joint names in the URDF have to match those in the openni_camera package (openni_camera/launch/kinect_frames.launch).

Start Up Kinect sensor

Install ni stack 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"/>-->

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 window.

Wiki: pr2_calibration/Tutorials/KinectURDFCalibration (last edited 2011-11-27 20:01:20 by KevinWatts)