Note: This tutorial assumes that you can provide the /camera/image_rect and /camera/camera_info input topics described in the overview.
(!) 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.

Detection in a Video Stream

Description: This tutorial teaches you how to use this package for tag and tag bundle detection in a video stream.

Tutorial Level: BEGINNER

Next Tutorial: Bundle Calibration

Note: For the tag pose estimation to work properly, your camera_info topic must be appropriately set with your camera calibration parameters (see this Github issue).

The most common use case for this package is to detect tags in a continuous stream of images (video frames) coming from a camera. This tutorial teaches you how to do this.

Parameter Setup

config/settings.yaml

This file sets parameters for the core AprilTag 2 algorithm and for the ROS wrapper. Use it in order to set these parameters. In particular:

  • Make sure that the tag_family is correct for the tags that you're using. The AprilTag 2 algorithm does not support simultaneous detection of multiple tag families;

  • Make sure tag_border corresponds to your tags' black border bit width (typically 1 - each square in the tag is represents 1 bit);

  • Setting tag_threads allows certain parts of the core AprilTag 2 algorithm to run parallel computations. Typical multithreading advantages and limitations apply;

  • Setting tag_decimate>1 allows to decimate (reduce the resolution) of the image by that amount. This makes the core AprilTag 2 algorithm faster (there are less pixels to process) but means that smaller tags are less likely to be detected. Pose estimation and decoding still happens with the full-resolution image;

  • Setting tag_blur>0 blurs the image and tag_blur<0 sharpens the image;

  • Setting tag_refine_edges=1 improves the detection fit to the tag, thus the corner detection precision, thus the pose estimation accuracy. Not computationally expensive and recommended to be on (1);

  • Setting tag_refine_decode=1 reducecs the false negative detetion rate;

  • Setting tag_refine_pose=1 improves the estimated pose accuracy but is computationally expensive;

  • Setting tag_debug=1 will save the AprilTag 2 algorithm's intermediate images into ~/.ros. This is useful for debugging a bad detection and should be used typically only with the single image detector;

  • Setting publish_tf=true will publish the detected tags' and tag bundles' poses over the /tf topic, meaning that they can be visualized in e.g. rviz.

config/tags.yaml

This file defines the standalone tags and tag bundles that should be looked for in the input image. Rogue tags (i.e. those that are not defined in config/tags.yaml) will be ignored. IMPORTANT:

  • No tag ID should appear twice with different sizes (this creates ambiguity in the detection);
  • No tag ID should appear twice in the image (this creates ambiguity in the detection);
  • It is fine for a tag with the same ID to be listed both in standalone_tags and in tag_bundles, as long as it has the same size.

Furthermore, make sure that you print yours tags surrounded by at least a 1 bit wide white border. The core AprilTag 2 algorithm samples this surrounding white border for creating a light model over the tag surface so do not e.g. cut or print the tags out flush with their black border.

The tag_bundles are filled out with the relative poses of the constituent tags to the bundle origin. Sometimes you may know these transforms (e.g. you print the bundle on a single sheet of paper where you lay out the tags in a known fashion). When you do not know these relative poses (e.g. you stick individual tags roughly on the floor/wall), perform a calibration to easily determine them.

launch/continuous_detection.launch

The launch file provides an opportunity to set a few more parameters. Here, the camera name and image topic can be remapped to your implementation. Furthermore, you can set the publish_tag_detections_image=false in order to not publish the /tag_detections_image (more efficient if you do not care to see an image with the detected tags highlighted).

Run the Detector

With the parameters correctly configured and the camera image stream being published, running the detector is trivial:

$ roslaunch apriltags2_ros continuous_detection.launch

Example

Consider the following config/settings.yaml:

tag_family:        'tag36h11'
tag_border:        1 
tag_threads:       2 
tag_decimate:      1.0 
tag_blur:          0.0 
tag_refine_edges:  1 
tag_refine_decode: 0 
tag_refine_pose:   0 
tag_debug:         0 
publish_tf:        true

Consider the following config/tags.yaml:

standalone_tags:
  [
    {id: 10, size: 0.15},
    {id: 20, size: 0.1},
    {id: 30, size: 0.07}
  ]
tag_bundles:
  [
    {
      name: 'my_bundle',
      layout:
        [
          {id: 0, size: 0.05, x: 0.0000, y: 0.0000, z: 0.0, qw: 1.0, qx: 0.0, qy: 0.0, qz: 0.0},
          {id: 4, size: 0.05, x: 0.0548, y: -0.0522, z: 0.0, qw: 1.0, qx: 0.0, qy: 0.0, qz: 0.0},
          {id: 3, size: 0.05, x: -0.0580, y: -0.0553, z: 0.0, qw: 1.0, qx: 0.0, qy: 0.0, qz: 0.0},
          {id: 2, size: 0.05, x: 0.0543, y: 0.0603, z: 0.0, qw: 1.0, qx: 0.0, qy: 0.0, qz: 0.0},
          {id: 1, size: 0.05, x: -0.0582, y: 0.0573, z: 0.0, qw: 1.0, qx: 0.0, qy: 0.0, qz: 0.0}
        ]
    }
  ]

We start the camera (Dell XPS 13 9360 webcam with 640x480 [px] resolution), the detector, run rqt and view the /tag_detections_image and the detected tags' and tag bundles' poses in rviz (thanks to /tf):

With these settings, the detection runs at roughly 15-20 Hz on the Dell XPS 13 9360 laptop with a 640x480 [px] resolution video stream. According to Valgrind (Callgrind with KCachegrind), the performance bottleneck is the core AprilTag 2 algorithm.

Wiki: apriltag_ros/Tutorials/Detection in a video stream (last edited 2019-05-02 07:09:46 by rgreid)