Note: This tutorial assumes that you can run MATLAB R2016b or later. This will be necessary until a Python version of the bundle calibration script is created.
(!) 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.

Bundle Calibration

Description: This tutorial teaches you how to calibrate a tag bundle for inclusion in config/tags.yaml.

Tutorial Level: BEGINNER

Next Tutorial: Detection in a Single Image

A tag bundle is a collection of AprilTags that are used simulataneously in order to extract a single "bundle pose", rather than the poses of the individual tags. This is useful when a more accurate and precise pose estimate is required since bundle pose estimation makes use of every detected tags' corners (making for 4n points if n tags are detected) rather than single tag pose estimation, which only uses 4 points corresponding to the 4 tag corners.

Bundle calibration is the determination of the relative pose of each tag with respect to the bundle frame. When you print the bundle on a single sheet of paper, you might know these relative poses exactly and calibration described herein is not necessary (you can fill out config/tags.yaml directly). However, when you lay out individual tags arbitrarily, the calibration herein allows to automatically determine the relative poses. For the theory behind this calibration, please refer to Section 3.1.4 of this report.

DANGER!!! Calibration accuracy strongly effects bundle detection accuracy. When you know the exact calibration (i.e. the bundle is arranged in a known precise fashion because it is e.g. printed on a single sheet of paper), use it instead of running this calibration. When you do run the calibration herein, ensure that bundle detection is accurate for an exhaustive number of bundle-camera relative poses. A common failure mode associated with a poor calibration is for the pose estimate to be "mirrored" (i.e. as if the bundle is behind the camera) for certain "unfortunate" bundle-camera relative poses.

Collecting Calibration Data

The first step in the calibration process is to collect the raw data in the form of a ROS bag. Let's assume without loss of generality that we are calibrating the following tag bundle:

bundle_sample.png

In this case, the bundle consists of tags of the family 36h11 with IDs 0, 1, 2, 3 and 4 that are all 50mm in side length. Fill out config/tags.yaml like so:

standalone_tags:
  [
    {id: 0, size: 0.05},
    {id: 1, size: 0.05},
    {id: 2, size: 0.05},
    {id: 3, size: 0.05},
    {id: 4, size: 0.05}
  ]
tag_bundles:
  [
  ]

Note that it is not an issue if there are more tags specified in config/tags.yaml as long as these ones are present with the correct side lengths in the standalone_tags list. Make sure that config/settings.yaml also sets the correct parameter values (e.g. tag_family: 'tag36h11' here). The idea is that we are now collecting the pose estimates of the individual tags with respect to the camera.

For this tutorial and without loss of generality we shall choose the center tag with ID 0 to be the master tag. The master tag's frame defines the bundle frame. If your bundle frame does not coincide with one of the constituent tags, add an extra tag just for the calibration to act as the master tag (you can remove it afterwards).

Position the camera in front of the bundle such that all constituent tags are visible. Keep the camera still during the data collection process. Now run the continuous tag detector:

$ roslaunch apriltags2_ros continuous_detection.launch

As explained in the apriltags2_ros overview, it is of course assumed that you have set up your camera corretly to publish on the camera image input topics subscribed to by the continuous detector. A typical /tag_detections_image during the calibration looks like this:

calibration_sample.png

Now run the following command to record the raw calibration data in the scripts/data directory:

$ rosbag record -O calibration /tag_detections

Keep recording until, heuristically speaking, about 500 /tag_detections messages are collected. If the /tag_detections topic is published at e.g. 10 Hz (this depends on how powerful your computer is and your choices in config/settings.yaml), then this means you should run the recording for roughly 1 minute.

In summary, you now have a raw calibration data bagfile with the file path scripts/data/clibration.bag. As far as calibration is concerned, you can now shut down ROS (the rest is MATLAB).

Running the Calibration

Open MATLAB and navigate to scripts/. Open calibrate_bundle.m for editing and set the master_id in the User inputs section to your calibration's master tag's ID. Here, we set master_id = 0. You can also set a custom bundle name and optionally a differently named .bag file to use for the raw calibration data. Now run in the command window:

>> calibrate_bundle

On first execution, the script will download and set up matlab_rosbag for reading ROS bag files in MATLAB. Then, the calibration script will run and an entry of tag_bundles will be printed out. For the bundle used in this tutorial, the following is printed:

tag_bundles:
  [
    {
      name: 'my_bundle',
      layout:
        [
          {id: 0, size: 0.05, x: 0.0000, y: 0.0000, z: 0.0000, qw: 1.0000, qx: 0.0000, qy: 0.0000, qz: 0.0000},
          {id: 4, size: 0.05, x: 0.0548, y: -0.0522, z: -0.0057, qw: 1.0000, qx: 0.0063, qy: -0.0016, qz: 0.0010},
          {id: 3, size: 0.05, x: -0.0580, y: -0.0553, z: 0.0015, qw: 1.0000, qx: -0.0039, qy: -0.0006, qz: 0.0016},
          {id: 2, size: 0.05, x: 0.0543, y: 0.0603, z: -0.0043, qw: 1.0000, qx: -0.0016, qy: 0.0082, qz: 0.0018},
          {id: 1, size: 0.05, x: -0.0582, y: 0.0573, z: 0.0012, qw: 1.0000, qx: -0.0057, qy: -0.0028, qz: 0.0006}
        ]
    }
  ]

You can directly copy this entry into config/tags.yaml. Note that, naturally, the master tag (here tag ID 0) has zero translation and identity quaternion attitude with respect to itself.

Wiki: apriltag_ros/Tutorials/Bundle calibration (last edited 2019-05-02 07:11:14 by rgreid)