Show EOL distros: 

Package Summary

A ROS wrapper of the AprilTag 3 visual fiducial detection algorithm. Provides full access to the core AprilTag 3 algorithm's customizations and makes the tag detection image and detected tags' poses available over ROS topics (including tf). The core AprilTag 3 algorithm is extended to allow the detection of tag bundles and a bundle calibration script is provided (bundle detection is more accurate than single tag detection). Continuous (camera image stream) and single image detector nodes are available.

Package Summary

A ROS wrapper of the AprilTag 3 visual fiducial detection algorithm. Provides full access to the core AprilTag 3 algorithm's customizations and makes the tag detection image and detected tags' poses available over ROS topics (including tf). The core AprilTag 3 algorithm is extended to allow the detection of tag bundles and a bundle calibration script is provided (bundle detection is more accurate than single tag detection). Continuous (camera image stream) and single image detector nodes are available.

Package Summary

A ROS wrapper of the AprilTag 3 visual fiducial detection algorithm. Provides full access to the core AprilTag 3 algorithm's customizations and makes the tag detection image and detected tags' poses available over ROS topics (including tf). The core AprilTag 3 algorithm is extended to allow the detection of tag bundles and a bundle calibration script is provided (bundle detection is more accurate than single tag detection). Continuous (camera image stream) and single image detector nodes are available.

Overview

io_diagram.png

The package works as shown in the above figure. The following default input topics are subscribed to (which can be remapped based on your needs):

  • /camera_rect/image_rect: a sensor_msgs/Image topic which contains the image (e.g. a frame of a video stream coming from a camera). The image is assumed to be undistorted, i.e. produced by a pinhole camera. Laptop webcams typically already provide such an image while other cameras may require undistortion by an intermediate node such as image_proc;

  • /camera_rect/camera_info: a sensor_msgs/CameraInfo topic which contains the camera calibration matrix in /camera/camera_info/K. One can obtain a specific camera's K via camera intrinsics calibration using e.g. camera_calibration or Kalibr (the former seemed to work better for laptop webcam calibration).

The behavior of the ROS wrapper is fully defined by the two configuration files config/tags.yaml (which defines the tags and tag bundles to look for) and config/settings.yaml (which configures the core AprilTag 2 algorithm itself). Then, the following topics are output:

  • /tf: relative pose between the camera frame and each detected tag's or tag bundle's frame (specified in tags.yaml) using tf. Published only if publish_tf: true in config/settings.yaml;

  • /tag_detections: the same information as provided by the /tf topic but as a custom message carrying the tag ID(s), size(s) and geometry_msgs/PoseWithCovarianceStamped pose information (where plural applies for tag bundles). This is always published;

  • /tag_detections_image: the same image as input by /camera/image_rect but with the detected tags highlighted. Published only if publish_tag_detections_image==true in launch/continuous_detection.launch.

Tutorials

The tutorials teach you how to operate the wrapper. The main idea is to fill out config/tags.yaml with the standalone tags and tag bundles which you would like to detect (bundles potentially require a calibration process) and config/settings.yaml with the wrapper and AprilTag 2 core parameters. Then, you simply run the continuous or single image detector. The tutorials walk you through how to do this.

Citing

While this ROS wrapper is original code originating from the author's master thesis, the core AprilTag 2 algorithm in apriltags2/ is wholly the work of the APRIL Robotics Lab at The University of Michigan. If you use this package, please kindly cite:

@mastersthesis{malyuta:2017mt,
  author = {Danylo Malyuta},
  title = {{Guidance, Navigation, Control and Mission Logic for Quadrotor Full-cycle Autonomy}},
  language = {english},
  type = {Master thesis},
  school = {Jet Propulsion Laboratory},
  address = {4800 Oak Grove Drive, Pasadena, CA 91109, USA},
  month = dec,
  year = {2017}
}
@inproceedings{Wang2016,
  author = {Wang, John and Olson, Edwin},
  booktitle = {2016 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},
  doi = {10.1109/IROS.2016.7759617},
  isbn = {978-1-5090-3762-9},
  month = {oct},
  pages = {4193--4198},
  publisher = {IEEE},
  title = {{AprilTag 2: Efficient and robust fiducial detection}},
  year = {2016}
}

Nodes

apriltag_ros

Detector for a continuous image (i.e. video) stream.

Subscribed Topics

image_rect (sensor_msgs/Image)
  • Undistorted image (i.e. produced by a pinhole camera)
camera_info (sensor_msgs/CameraInfo)
  • Camera information, used only for the camera calibration matrix K

Published Topics

tag_detections (apriltag_ros/AprilTagDetectionArray)
  • Array of tag and tag bundle detections' pose relative to the camera
tag_detections_image (sensor_msgs/Image)
  • Same as image_rect but with the detected tags highlighted

Parameters

tag_family (string, default: tag36h11)
  • AprilTag family to use for detection. Supported: tag36h11, tag36h10, tag25h9, tag25h7 and tag16h5.
tag_border (int, default: 1)
  • Width of the tag outer (circumference) black border
tag_threads (int, default: 4)
  • How many threads should the AprilTag 2 core algorithm use?
tag_decimate (double, default: 1.0)
  • Detection of quads can be done on a lower-resolution image, improving speed at a cost of pose accuracy and a slight decrease in detection rate. Decoding the binary payload is still done at full resolution. .
tag_blur (double, default: 0.0)
  • What Gaussian blur should be applied to the segmented image (used for quad detection?) Parameter is the standard deviation in pixels. Very noisy images benefit from non-zero values (e.g. 0.8).
tag_refine_edges (int, default: 1)
  • When non-zero, the edges of the each quad are adjusted to "snap to" strong gradients nearby. This is useful when decimation is employed, as it can increase the quality of the initial quad estimate substantially. Generally recommended to be on (1). Very computationally inexpensive. Option is ignored if tag_decimate==1.0.
tag_refine_decode (int, default: 0)
  • When non-zero, detections are refined in a way intended to increase the number of detected tags. Especially effective for very small tags near the resolution threshold (e.g. 10px on a side).
tag_refine_pose (int, default: 0)
  • When non-zero, detections are refined in a way intended to increase the accuracy of the extracted pose. This is done by maximizing the contrast around the black and white border of the tag. This generally increases the number of successfully detected tags, though not as effectively (or quickly) as tag_refine_decode.
publish_tf (bool, default: false)
  • Enable publishing the tag-camera relative poses on the /tf topic
camera_frame (string, default: camera)
  • Camera frame name
publish_tag_detections_image (bool, default: false)
  • Enable publishing on the /tag_detections_image topic

Provided tf Transforms

tagcamera
  • Relative pose of the camera frame to the tag frame. The tag frame here is a placeholder for a standalone tag frame or a tag bundle frame and the specific name can be specified in config/tags.yaml or will be set automatically to tag_ID or bundle_COUNT if ommitted. There will be as many of these transforms as there are specified tags and tag bundles in config/tags.yaml.

apriltag_ros_single_image_server

Detector of tags in a single provided image (via a ROS service which it serves). This is useful for e.g. analyzing a single frame of a video stream (which you maybe think had a faulty tag detection). Starting with, as a baseline, the same description as the apriltag_ros node, this node does not subscribe to any topics, does not output the /tag_detections_image topic (the output image is saved in an image save filepath as described below) and does not use the parameters camera_frame and publish_tag_detections_image. The information below describes additional features of this node.

Services

single_image_tag_detection (apriltag_ros/AnalyzeSingleImage)
  • Takes in the absolute file path of the input image to detect tags in, the absolute file path where to store the output image (same as input image, with detected tags highlighted) and the camera intrinsics (in particular, the K matrix). Returns an apriltag_ros/AprilTagDetectionArray of the detected tags' and tag bundles' poses.

apriltag_ros_single_image_client

A client for the single image tag detection service provided by the apriltag_ros_single_image_server node. This node is developed specifically for interacting with this service. Starting with, as a baseline, the same description as the apriltag_ros node, this node does not subscribe to any topics, does not publish any topics and does not use the parameters camera_frame and publish_tag_detections_image. The information below describes additional features of this node.

Services Called

single_image_tag_detection (apriltag_ros/AnalyzeSingleImage)

Parameters

image_load_path (string)
  • Absolute file path of the image to detect tags in
image_save_path (string)
  • Absolute file path where to save the image with the detected tags highlighted
fx (double)
  • Camera x focal length (in [px])
fy (double)
  • Camera y focal length (in [px])
cx (double)
  • Camera image principal point x coordinate (in [px])
cy (double)
  • Camera image principal point y coordinate (in [px])

Wiki: apriltag_ros (last edited 2022-10-15 09:19:17 by LennartWachowiak)