[Documentation] [TitleIndex] [WordIndex

ipa_calibration

Code at https://github.com/ipa320/ipa_calibration.

Overview

The ipa_calibration project contains packages that allow for optimizing uncertain extrisic transforms within a robot's kinematic tree. The project contains out of five packages:

The ipa_calibration_interface package contains full implementations of the calibration_interface class for several robots (rob@work, squirrel robotino, care-o-bot 4) which is provided by the libcalibration package. Furthermore, it provides nodes for detecting checkerboards and pitags in the environment utilizing a suitable rgb camera of the robot. The cameras that are being used in the process have to be calibrated beforehand. This package can fully be replaced by an other one that implements the calibration_interface class and provides all other methods to move the robot or parts of it and detect the transforms needed and publishes them to TF. For further information take a look at the section about this topic.

The jointstate_saver package is not part of the actual calibration routine. It allows the user to capture joint states of cameras or arms of the robot to build collision-free trajectories that can be used for the calibration routine afterwards.

The libcalibration package contains all the necessary code to optimize uncertain transforms and save the results to the drive. The package provides an abstract calibration_interface class that can be derived from the user to set up a calibration routine for custom robots. All necessary transforms for the calibration process have to be available from TF in order to be usable.

The relative_localization package provides methods to set up a reference coordinate system in the environment which can be used in the calibration process when markers are attached to the environment. It also provides an orientation to which the robot's base can be moved against. There are two options provided, building a reference coordinate system by either using a corner of two walls or a box. The packages makes use of the laserscanners of a robot, which have to be calibrated beforehand.

The transfer_calibration packages contains code in order to move the calibration results from its source file to a destination file and replace the corresponding parameters in there. However, the package in no longer maintained and parameters should be updated manually.

Creating a custom calibration interface package

The libcalibration package provides a general interface class (calibration_interface) which has to be implemented for each robot that is going to be used for calibration. The interface provides the following methods:

   1 virtual bool moveRobot(int current_index) = 0;

This method is called by the robot_calibration.cpp whenever the robot shall do its next move, the current_index parameter is a counter that counts upwards in a loop with before every call of moveRobot().

   1 virtual int getConfigurationCount() = 0;

The method is called in a loop within robot_calibration.cpp in order to find out how often to execute moveRobot()

   1 virtual void preSnapshot(int current_index) = 0;

Snapshots of all relevant TF transforms will be done by robot_calibration.cpp after having successfully executed moveRobot(). Before those snapshots will be taken, preSnapshot() will be called with the index of the current configuration that was executed in moveRobot() before. This methods gives the user the chance to execute some code before any snapshot happens (e.g. wait for transforms that have to be detected to be updated in TF, wait to mitigate shaking effects in robot's kinematic after moving, etc...)

   1 virtual void getPatternPoints3D(const std::string marker_frame,
   2                                 std::vector<cv::Point3f> &pattern_points_3d) = 0;

This method will be called at the end of the calibration routine, when the uncertain transforms are calculated. The pattern points (in 3 dimensions) of each marker relative to the marker's local frame needs to be stored to the pattern_points_3d parameter. The name of each marker (marker_frame) will be passed over to the method and therefore markers can have different patterns, hence one can mix pitags, checkerboards, etc... Ensure that static and detected frames of the same marker have the same pattern.

   1 virtual void getCalibrationSettings(std::vector<std::string> &uncertainties_list,
   2                                     int &optimization_iterations,
   3                                     double &transform_discard_timeout,
   4                                     std::string &calibration_storage_path) = 0;

This method will be called during the initialization process of a RobotCalibration object, so it can be set up correctly. The user has to pass over the corresponding values. Parameter description:

   1 virtual std::string getFileName(const std::string &appendix,
   2                                 const bool file_extension) = 0;

The method will be called at the end of a calibration process when storing the results to the given calibration_storage_path (see getCalibrationSettings()). It is used to generate a filename for the output files of the results. Two files will be created, the file with the calibration results and an other one which holds all relevant TF transforms in order to perform an offline calibration without being connected to the robot. In order to trigger the offline calibration the load_data flag has to be set to true when creating a RobotCalibration object. But the offline calibration has its limits, one can only swap the order of the uncertain transforms but can't calibrate new ones. For the results file, the appendix is set to "results" and for the offline data it is "offline_data". The results file can have a user-defined file extension, therefore file_extension is true, but the offline data it is forced to .txt so don't add a file extension by yourself here (file_extension equals false).

In order to start the calibration, one has to create a RobotCalibration object inside a try-catch block:

   1 try
   2 {
   3         RobotCalibration calib_obj(&nh, interface, load_data);
   4         calib_obj.startCalibration();
   5 }
   6 catch ( std::exception &e )
   7 {
   8         return -1;
   9 }

The parameter &nh is the address to the node handle of the current ros node, interface is a pointer to the interface instance that has been created beforehand and load_data specifies whether to perform an offline calibration or not. Do not forget to include following headers:

   1 #include <libcalibration/robot_calibration.h>
   2 #include <libcalibration/calibration_interface.h>
   3 

Take a look at ipa_calibration_interface/ros/src for examples about how to set up everything (camera_laserscanner_calibration_node.cpp and camera_arm_calibration_node.cpp).

IPA Calibration Interface

The ipa_calibration stack offers a full implementation of a calibration interface package called ipa_calibration_interface which provides interfaces for different robot types that are relevant at the Fraunhofer IPA. Such robots are rob@work, care-o-bot and squirrel robotino. The package also comes along with two detection methods in order to detect pitags and checkerboards in the environment.

Camera-Laserscanner Calibration

This type of calibration makes use of cameras and laserscanners of the robot in order to calibrate extrinsic transforms. The robot and its cameras will be moved around to capture data from different positions and angles. The routine makes use of the relative_localization package in order to set up a reference frame for robot movement and marker placement.

Requirements

Setting up the calibration environment

Before calibrating the robot one has to select an appropriate place for attaching some markers in the environment. The localization of the robot in this environment will be done using the relative_localization package. This package offers two ways for localizing the robot, the box detection and the corner detection which both utilize the laserscanners of the robot in use. In either case, the front wall has to be detected. That wall is the one the robot is facing, so ensure that the x-axis of the chosen base_frame (see yaml files) is pointing towards the wall and that the front wall normal does not span an angle over 45° with that x-axis, otherwise the front wall won't be detected anymore. That means that the robot's base should not be rotated too much during the calibration process.

Box detection

This method requires a flat wall segment, i.e. there should not be any objects around. In the center of this wall segment place a small box, which is higher than the laser scanner mounting height and which has to touch the wall. The box must stand apart from the wall by more than 10 cm. The box is used to localize the calibration pattern with the laser scanner. Similarly, place robot somwhere at the center of the wall segment facing the box with its laser scanner.

The search algorithm will use all laserscanner points within the defined box_search_polygon to find the box. The other points inside the front_wall_polygon contribute to finding the front wall.

The setup should look similar to the following examples. The last image visualizes the reference coordinate system (here: landmark_reference_nav) which has the same orientation as the base link of the robot and which is located at the intersection of the left box edge and the wall at ground level.

Box localization setup Box localization setup Box localization setup Box localization setup

There are some properties you may want to edit in order to match your calibration environment well. These properties can be found in the ipa_calibration/relative_localization/ros/launch/settings/box_localization_params_ROBOT.yaml file.

# Defines how fast new measurements are averaged into the transformation estimate (new_value = (1-update_rate)*old_value + update_rate*measurement). [0,1]
# double
update_rate: <update_rate>

# The name of the computed reference frame.
# string
reference_frame: <ref_frame>

# height above ground of base frame
# double
base_height: <base_height>

# Chosen base link of robot that is used to build the reference frame upon.
# string
base_frame: <base_link>

# frame which is used to filter out wall points, it can be assigned with an existing frame or a yet unknown frame
# Existing frame: Polygons for detection wall points will be build upon the assigned existing frame (e.g. robot's base)
# Unknown frame: A new frame will be generated at startup upon the first reference_frame detection (from reference_frame to base_frame)
# The frame will be set up once at startup and stays fixed from that time on which prevents that robot rotations mess up the reference frame detection.
# string
polygon_frame: <polygon_frame>

# laser scanner topic
# string
laser_scanner_topic_in: <laser_topic>

# Polygon points that define the closed area which is used to find the front wall inside.
# Includes x and y coordinates [in m] of each point that define the polygon in the robot's base frame. Input at least 4 points for a closed region. Do not forget to repeat the first point at the end.
# Relative to polygon_frame
# vector<Point2f>
front_wall_polygon: [X1, Y1,
                     X2, Y2,
                     X3, Y3, ...]

# Polygon points that define the closed area which is used to find the box inside.
# Includes x and y coordinates [in m] of each point that define the polygon in the robot's base frame. Input at least 4 points for a closed region. Do not forget to repeat the first point at the end.
# vector<Point2f>
box_search_polygon: [X1, Y1,
                     X2, Y2,
                     X3, Y3, ...]

# Example of a closed polygon
box_search_polygon: [0.3, 0.5,
                     1.5, 0.5,
                     1.5, -0.5,
                     0.3, -0.5,
                     0.3, 0.5]

One has to define polygons which will be used to reliably detect the reference coordinate system. The image above shows an example of those polygons, the front_wall_polygon is shown in red whereas the box_search_polygon is shown in orange. The visualization of the polygons will be published in a Marker-topic and can be viewed using Rviz. Those polygons can have their own polygon_frame which will be spawned once at startup relative to the detected reference_frame using the given base_frame of the robot as initialization. However, this will only happen when the polygon_frame does not already exist in TF or is outdated. This feature allows that the polygons stay at a fixed position independent from robot movement.

Corner detection

This approach localizes the robot against a corner of two perpendicular walls. Ensure that there are no objects around that corner (in a 2-3 m range) because they could interfere with the correct localization of the corner. The robot should be placed facing one of these walls, as you can see in the following images. The second image visualizes the reference coordinate system which has the same orientation as the base link of the robot and which is located at the intersection of the two walls at ground level.

Corner localization setup Corner localization setup Corner localization setup

The search algorithm will use all laserscanner points within the defined side_wall_polygon to find the side wall. The other points inside the front_wall_polygon contribute to finding the front wall. The software automatically picks the frontal wall first and then seeks the best fitting perpendicular line resulting from the side_wall_polygon laserscanner points.

There are some properties you may want to edit in order to match your calibration environment well. These properties can be found in the squirrel_calibration/relative_localization/ros/launch/settings/corner_localization_params_ROBOT.yaml file

# Defines how fast new measurements are averaged into the transformation estimate (new_value = (1-update_rate)*old_value + update_rate*measurement). [0,1]
# double
update_rate: <update_rate>

# The name of the computed child frame.
# string
reference_frame: <ref_frame>

# height above ground of base frame
# double
base_height: <base_height>

# Chosen base link of robot that is used to build the reference frame upon.
# string
base_frame: <base_link>

# frame which is used to filter out wall points, it can be assigned with an existing frame or a yet unknown frame
# Existing frame: Polygons for detection wall points will be build upon the assigned existing frame (e.g. robot's base)
# Unknown frame: A new frame will be generated at startup upon the first reference_frame detection (from reference_frame to base_frame)
# The frame will be set up once at startup and stays fiixed from that time on which prevents that robot rotations mess up the reference frame detection.
# string
polygon_frame: <polygon_frame>

# laser scanner topic
# string
laser_scanner_topic_in: <laser_topic>

# Polygon points that define the closed area which is used to find the front wall inside.
# Includes x and y coordinates [in m] of each point that define the polygon in the robot's base frame. Input at least 4 points for a closed region. Do not forget to repeat the first point at the end.
# Relative to polygon_frame
# vector<Point2f>
front_wall_polygon: [X1, Y1,
                     X2, Y2,
                     X3, Y3, ...]

# Polygon points that define the closed area which is used to find the side wall inside.
# Includes x and y coordinates [in m] of each point that define the polygon in the robot's base frame. Input at least 4 points for a closed region. Do not forget to repeat the first point at the end.
# Relative to polygon_frame
# vector<Point2f>
side_wall_polygon: [X1, Y1,
                    X2, Y2,
                    X3, Y3, ...]

One again has to define polygons that are used to detect the reference frame reliably. The image above shows the front_wall_polygon in red and the side_wall_polygon in orange. Take a look at the Box Detection section for more information about polygons.

Placing markers

After having decided for a detection method one has to attach markers to the environment. Markers can either be checkerboards or pitags. Each marker that has been placed needs to to be added as static TF transform in its respective setup launch file (pitag_setup.launch or checkerboard_marker.launch) so it can be loaded at startup. The position of each marker has to be manually measured relative to the reference frame which will be created by the detection method. It is recommended that the static frames are aligned (rotation and position) the same way as their counterparts that are going to be detected by the cameras.

Checkerboard frame

The Checkerboard frame image shows how the internal frame of the checkerboard is aligned. The origin is located at the second cell on the diagonal. Ensure that the detected and the static frames are as aligned the same way. The x-axis of the checkerboard (red) is going from left to right and the y-axis (green) is pointing downwards. The z-axis is pointing into the plane.

Pitag frame

The Pitag frame image shows how the internal frame of a pitag is aligned. The x-axis (red) is pointing from left to right while the y-axis (green) is pointing upwards. The z-axis is pointing out of the plane. The origin is located at the circle with the cross inside.

Setting up the calibration parameters

Simulation

When you have downloaded and installed the optional repository (check the Requirements section for installation) you can run a new command in the terminal. This command will bring up a simulated robotino robot that can be used to get into the calibration code.

roslaunch robotino_bringup_sim robot.launch robot:=tuw-robotino2 robot_env:=calibration-room marker:=<marker>

Parameters:

Camera-Arm Calibration

This type of calibration makes use of cameras and arms of the robot in order to calibrate extrinsic transforms. The routine makes use of the checkerboard detection. The robot's base will not be moved around but instead one or more arms will be moved. That does also mean that there is no reference frame being set up. Each arm needs to have a checkerboard attached to it.

Requirements

One or more arms need to have a checkerboard pattern mounted on one of their joints. The following image shows an example of an endeffector holding a checkerboard that can be mounted on top of the gripper frame of a robot's arm.

Checkerboard gripper

When adding the checkerboard frame as static transform to the checkerboard_marker.launch ensure that it is aligned properly. You find more about that in the Placing markers section of the Camera-Laserscanner Calibration chapter.

Setting up the calibration parameters

Adding a new robot

It is fairly easy to add new robots to the existing ipa_calibration_interface:

Multi camera systems

The ipa_calibration_interface package does not support different types of markers to be mixed within one calibration setup, so decide either for using checkerboards or pitags. In case you have to use more than one checkerboard, make sure they have the same pattern, otherwise one has to extend the ipa_calibration/ipa_calibration_interface/ros/src/checkerboard_marker.cpp file in order to support different types of checkerboards. When using several similar checkerboards and several cameras at once one has to consider that every camera can detect every checkerboard on sight which can lead to bad results. Take into account, that each camera needs to have its own detection node being started at startup. That means that the pitag_setup.launch or the checkerboard_setup.launch within the ipa_calibration/ipa_calibration_interface/ros have to be extended for every additional camera in use.

Report a Bug

Use GitHub to report bugs or submit feature requests. [View active issues]


2024-12-28 14:59