!

Note: The whole calibration process is not complete yet for the Care-O-bot 4. This tutorial only explains the current unfinished state of the calibration procedure..
(!) 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.

Configure robot for calibration

Description: This tutorial explains how to configure the Care-O-bot 4 for calibration.

Tutorial Level: INTERMEDIATE

Overview

This tutorial explains how to configure a robot for the calibration procedure.

All the robot specific parameters are located in the cob_calibration_config package. For each robot there is a folder called user_defined where all the parameters that the user should care about are located.

Attaching a checkerboard model to a robot arm

First of all, whether running in simulation or on the real hardware, the calibration pattern model, including its collision model, should be attached to the robot model.

The model for 6x9 checkerboard is located in the user_defined folder in file named cb_9x6.urdf.xacro. This file should be included in the robot model which is located in cob_hardware_config package. For cob4-2 the robot model file name is cob4-2.urdf.xacro.

The checkerboard is attached to the robot model with the following include tag:

<robot>
  # other stuff
  <xacro:include filename="/FILE_PATH/cb_9x6.urdf.xacro" />
</robot>

Configure generate_positions_config.yaml

In generate_positions_config.yaml we define the parameters for each arm we want to generate the calibration positions.

Here is an example how the file should look like:

arms:
  arm_1:
    name: arm_left                      # Name of the MoveIt planning group
    limits_corner_1: [0.0, 0.30, 0.2]           # x1, y1, z1            
    limits_corner_2: [-0.50, -0.30, 0.8]        # x2, y2, z2
    discritization: [3,3,3]                     # Discretisation of x, y, z
    hand_orientation: [0.5, 0.5, 0.5, 0.5]              # End effector pose
    arm_planning_reference_frame: torso_cam3d_left_link # The limits and the orientation are defined relative to this frame

  arm_2:
    name: arm_right
    limits_corner_1: [0.0, 0.30, 0.2]
    limits_corner_2: [-0.50, -0.30, 0.8]
    discritization: [3,3,3]
    hand_orientation: [0.5, 0.5, 0.5, 0.5]
    arm_planning_reference_frame: torso_cam3d_right_link

The arm_planning_reference_frame refers to the camera that will be used to calibrate the arm in question.

With limits_corner values we create an imaginary cuboid which defines limits inside which the position generator will generate calibration positions for the end effector. The cuboid is created by defining two opposite corners in cartesian coordinates with respect to the arm_planning_reference_frame.

The discritization defines in to how many steps we discretise each dimension of the cuboid That is, with this value we control how many calibration positions we want to generate.

The hand_orientation should be defined so that the checkerboard plane is perpendicular to the arm_planning_reference_frame. You can use for example this converter to convert from Euler angles to Quaternion.

Configure cameras.yaml

In cameras.yaml we define the cameras used in the calibration:

reference:
        name: torso_cam3d_left_link
        topic: /torso_cam3d_left/rgb/image_raw
        cam_info_service: /torso_cam3d_left/set_camera_info
        file_prefix: left_kinect
        frame_id: /torso_cam3d_left_link

further:
       -        name: torso_cam3d_right_link
                topic: /torso_cam3d_right/rgb/image_raw
                cam_info_service: /torso_cam3d_right/set_camera_info
                file_prefix: right_kinect
                frame_id: /torso_cam3d_right_link
       -        name: torso_cam3d_down_link
                topic: /torso_cam3d_down/rgb/image_raw
                cam_info_service: /torso_cam3d_down/set_camera_info
                file_prefix: down_kinect
                frame_id: /torso_cam3d_down_link

The “cam_info_topic” is name of the service that sends the intrinsic camera calibration results to the camera driver. frame_id is the name of the camera link in the robot model. The rest parameter names should be self explanatory.

Wiki: cob_calibration/Tutorials/configuration_cob4_indigo (last edited 2015-08-12 12:18:25 by TopiasLiikanen)