Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
jazzy

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
kilted

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
rolling

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro ardent showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro bouncy showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro crystal showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro eloquent showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
dashing

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro galactic showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro foxy showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
iron

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro lunar showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro jade showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro indigo showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro hydro showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

No version for distro kinetic showing humble. Known supported distros are highlighted in the buttons above.
Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
humble

Repository Summary

Checkout URI https://github.com/christianrauch/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2025-05-06
Dev Status DEVELOPED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.2

README

AprilTag ROS 2 Node

This ROS 2 node uses the AprilTag library to detect AprilTags in images and publish their pose, id and additional metadata.

For more information on AprilTag, the paper and the reference implementation: https://april.eecs.umich.edu/software/apriltag.html

Topics

Subscriptions:

The node subscribes via a image_transport::CameraSubscriber to rectified images on topic image_rect. The set of topic names depends on the type of image transport (parameter image_transport) selected (raw or compressed):

  • image_rect (raw, type: sensor_msgs/msg/Image)
  • image_rect/compressed (compressed, type: sensor_msgs/msg/CompressedImage)
  • camera_info (type: sensor_msgs/msg/CameraInfo)

Publisher:

  • /tf (type: tf2_msgs/msg/TFMessage)
  • detections (type: apriltag_msgs/msg/AprilTagDetectionArray)

The camera intrinsics P in CameraInfo are used to compute the marker tag pose T from the homography H. The image and the camera intrinsics need to have the same timestamp.

The tag poses are published on the standard TF topic /tf with the header set to the image header and child_frame_id set to either tag<family>:<id> (e.g. “tag36h11:0”) or the frame name selected via configuration file. Additional information about detected tags is published as AprilTagDetectionArray message, which contains the original homography matrix, the hamming distance and the decision_margin of the detection.

Configuration

The node is configured via a yaml configurations file. For the complete ROS yaml parameter file syntax, see: https://github.com/ros2/rcl/tree/master/rcl_yaml_param_parser.

The configuration file has the format:

apriltag:                 # node name
  ros__parameters:
    # setup (defaults)
    image_transport: raw  # image format: "raw" or "compressed"
    family: 36h11         # tag family name: 16h5, 25h9, 36h11
    size: 1.0             # default tag edge size in meter
    profile: false        # print profiling information to stdout

    # tuning of detection (defaults)
    max_hamming: 0        # maximum allowed hamming distance (corrected bits)
    detector:
      threads: 1          # number of threads
      decimate: 2.0       # decimate resolution for quad detection
      blur: 0.0           # sigma of Gaussian blur for quad detection
      refine: 1           # snap to strong gradients
      sharpening: 0.25    # sharpening of decoded images
      debug: 0            # write additional debugging images to current working directory

    pose_estimation_method: "pnp" # method for estimating the tag pose

    # (optional) list of tags
    # If defined, 'frames' and 'sizes' must have the same length as 'ids'.
    tag:
      ids:    [<id1>, <id2>, ...]         # tag IDs for which to publish transform
      frames: [<frame1>, <frame2>, ...]   # frame names
      sizes:  [<size1>, <size1>, ...]     # tag-specific edge size, overrides the default 'size'

The family (string) defines the tag family for the detector and must be one of 16h5, 25h9, 36h11, Circle21h7, Circle49h12, Custom48h12, Standard41h12, Standard52h13. size (float) is the tag edge size in meters, assuming square markers.

Instead of publishing all tag poses, the list tag.ids can be used to only publish selected tag IDs. Each tag can have an associated child frame name in tag.frames and a tag specific size in tag.sizes. These lists must either have the same length as tag.ids or may be empty. In this case, a default frame name of the form tag<family>:<id> and the default tag edge size size will be used.

The remaining parameters are set to the their default values from the library. See apriltag.h for a more detailed description of their function.

See tags_36h11.yaml for an example configuration that publishes specific tag poses of the 36h11 family.

Nodes

Standalone Executable

The apriltag_node executable can be launched with topic remappings and a configuration file:

ros2 run apriltag_ros apriltag_node --ros-args \
    -r image_rect:=/camera/image \
    -r camera_info:=/camera/camera_info \
    --params-file `ros2 pkg prefix apriltag_ros`/share/apriltag_ros/cfg/tags_36h11.yaml

Composable Node

For more efficient intraprocess communication, a composable node is provided:

$ ros2 component types
apriltag_ros
  AprilTagNode

This AprilTagNode component can be loaded with other nodes into a “container node” process where they used shared-memory communication to prevent unnecessary data copies. The example launch file camera_36h11.launch.yml loads the AprilTagNode component together with the camera::CameraNode component from the camera_ros package (sudo apt install ros-$ROS_DISTRO-camera-ros) into one container and enables use_intra_process_comms for both:

ros2 launch apriltag_ros camera_36h11.launch.yml

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
melodic

Repository Summary

Checkout URI https://github.com/AprilRobotics/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2023-03-27
Dev Status MAINTAINED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.1

README

apriltag_ros

apriltag_ros is a Robot Operating System (ROS) wrapper of the AprilTag 3 visual fiducial detector. For details and tutorials, please see the ROS wiki.

apriltag_ros depends on the latest release of the AprilTag library. Clone it into your catkin workspace before building.

Authors: Danylo Malyuta, Wolfgang Merkt

Maintainers: Danylo Malyuta (Autonomous Control Laboratory, University of Washington), Wolfgang Merkt

Quickstart

Starting with a working ROS installation (Kinetic and Melodic are supported):

export ROS_DISTRO=melodic               # Set this to your distro, e.g. kinetic or melodic
source /opt/ros/$ROS_DISTRO/setup.bash  # Source your ROS distro 
mkdir -p ~/catkin_ws/src                # Make a new workspace 
cd ~/catkin_ws/src                      # Navigate to the source space
git clone https://github.com/AprilRobotics/apriltag.git      # Clone Apriltag library
git clone https://github.com/AprilRobotics/apriltag_ros.git  # Clone Apriltag ROS wrapper
cd ~/catkin_ws                          # Navigate to the workspace
rosdep install --from-paths src --ignore-src -r -y  # Install any missing packages
catkin build    # Build all packages in the workspace (catkin_make_isolated will work also)

See the ROS wiki for details and tutorials.

Tag Size Definition

For a correct depth estimation (and hence the correct full pose) it is necessary to specify the tag size in config/tags.yaml correctly. In the Wiki for the AprilTag Library the correct interpretation of the term “tag size” is explained. The size is defined by the length of the black/white border between the complete black and white rectangle of any tag type. Note that for apriltag3 marker families this does not in fact correspond to the outside of the marker.

Below is a visualization of the tag size (red arrow) to be specified for the most common tag classes: Tag Size Guide

Contributing

Pull requests are welcome! Especially for the following areas:

  • Publishing of the AprilTag 3 algorithm intermediate images over a ROS image topic (which AprilTag 3 already generates when tag_debug==1)
  • Conversion of the bundle calibration script from MATLAB to Python
  • Extend calibration to support calibrating tags that cannot appear simultaneously with the master tag, but do appear simultaneously with other tags which themselves or via a similar relationship appear with the master tag (e.g. a bundle with the geometry of a cube - if the master is on one face, tags on the opposite face cannot currently be calibrated). This is basically “transform chaining” and potentially allows calibration of bundles with arbitrary geometry as long as a transform chain exists from any tag to the master tag
  • Supporting multiple tag family detection (currently all tags have to be of the same family). This means calling the detector once for each family. Because the core AprilTag 2 algorithm is the performance bottleneck, detection of n tag families will possibly decrease performance by 1/n (tbd if this still holds for v3)

Changelog

  • In March 2019, the code was upgraded to AprilTag 3 and as thus the options refine_pose, refine_decode, and black_border were removed.

The source code in apriltag_ros/ is original code that is the ROS wrapper itself, see the LICENSE. It is inspired by apriltags_ros and provides a superset of its functionalities.

If you use this code, please kindly inform Danylo Malyuta (to maintain a list here of research works that have benefited from the code) and cite:

@article{Malyuta2019,
  doi = {10.1002/rob.21898},
  url = {https://doi.org/10.1002/rob.21898},
  pages = {arXiv:1908.06381},
  year = {2019},
  month = aug,
  publisher = {Wiley},
  author = {Danylo Malyuta and Christian Brommer and Daniel Hentzen and Thomas Stastny and Roland Siegwart and Roland Brockers},
  title = {Long-duration fully autonomous operation of rotorcraft unmanned aerial systems for remote-sensing data acquisition},
  journal = {Journal of Field Robotics}
}
@inproceedings{Brommer2018,
  doi = {10.1109/iros.2018.8594111},
  url = {https://doi.org/10.1109/iros.2018.8594111},
  pages = {arXiv:1810.05683},
  year  = {2018},
  month = {oct},
  publisher = {{IEEE}},
  author = {Christian Brommer and Danylo Malyuta and Daniel Hentzen and Roland Brockers},
  title = {Long-Duration Autonomy for Small Rotorcraft {UAS} Including Recharging},
  booktitle = {{IEEE}/{RSJ} International Conference on Intelligent Robots and Systems}
}
@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}
}

Repo symbol

apriltag_ros repository

apriltag_ros

ROS Distro
noetic

Repository Summary

Checkout URI https://github.com/AprilRobotics/apriltag_ros.git
VCS Type git
VCS Version master
Last Updated 2023-03-27
Dev Status MAINTAINED
Released RELEASED
Tags No category tags.
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

Name Version
apriltag_ros 3.2.1

README

apriltag_ros

apriltag_ros is a Robot Operating System (ROS) wrapper of the AprilTag 3 visual fiducial detector. For details and tutorials, please see the ROS wiki.

apriltag_ros depends on the latest release of the AprilTag library. Clone it into your catkin workspace before building.

Authors: Danylo Malyuta, Wolfgang Merkt

Maintainers: Danylo Malyuta (Autonomous Control Laboratory, University of Washington), Wolfgang Merkt

Quickstart

Starting with a working ROS installation (Kinetic and Melodic are supported):

export ROS_DISTRO=melodic               # Set this to your distro, e.g. kinetic or melodic
source /opt/ros/$ROS_DISTRO/setup.bash  # Source your ROS distro 
mkdir -p ~/catkin_ws/src                # Make a new workspace 
cd ~/catkin_ws/src                      # Navigate to the source space
git clone https://github.com/AprilRobotics/apriltag.git      # Clone Apriltag library
git clone https://github.com/AprilRobotics/apriltag_ros.git  # Clone Apriltag ROS wrapper
cd ~/catkin_ws                          # Navigate to the workspace
rosdep install --from-paths src --ignore-src -r -y  # Install any missing packages
catkin build    # Build all packages in the workspace (catkin_make_isolated will work also)

See the ROS wiki for details and tutorials.

Tag Size Definition

For a correct depth estimation (and hence the correct full pose) it is necessary to specify the tag size in config/tags.yaml correctly. In the Wiki for the AprilTag Library the correct interpretation of the term “tag size” is explained. The size is defined by the length of the black/white border between the complete black and white rectangle of any tag type. Note that for apriltag3 marker families this does not in fact correspond to the outside of the marker.

Below is a visualization of the tag size (red arrow) to be specified for the most common tag classes: Tag Size Guide

Contributing

Pull requests are welcome! Especially for the following areas:

  • Publishing of the AprilTag 3 algorithm intermediate images over a ROS image topic (which AprilTag 3 already generates when tag_debug==1)
  • Conversion of the bundle calibration script from MATLAB to Python
  • Extend calibration to support calibrating tags that cannot appear simultaneously with the master tag, but do appear simultaneously with other tags which themselves or via a similar relationship appear with the master tag (e.g. a bundle with the geometry of a cube - if the master is on one face, tags on the opposite face cannot currently be calibrated). This is basically “transform chaining” and potentially allows calibration of bundles with arbitrary geometry as long as a transform chain exists from any tag to the master tag
  • Supporting multiple tag family detection (currently all tags have to be of the same family). This means calling the detector once for each family. Because the core AprilTag 2 algorithm is the performance bottleneck, detection of n tag families will possibly decrease performance by 1/n (tbd if this still holds for v3)

Changelog

  • In March 2019, the code was upgraded to AprilTag 3 and as thus the options refine_pose, refine_decode, and black_border were removed.

The source code in apriltag_ros/ is original code that is the ROS wrapper itself, see the LICENSE. It is inspired by apriltags_ros and provides a superset of its functionalities.

If you use this code, please kindly inform Danylo Malyuta (to maintain a list here of research works that have benefited from the code) and cite:

@article{Malyuta2019,
  doi = {10.1002/rob.21898},
  url = {https://doi.org/10.1002/rob.21898},
  pages = {arXiv:1908.06381},
  year = {2019},
  month = aug,
  publisher = {Wiley},
  author = {Danylo Malyuta and Christian Brommer and Daniel Hentzen and Thomas Stastny and Roland Siegwart and Roland Brockers},
  title = {Long-duration fully autonomous operation of rotorcraft unmanned aerial systems for remote-sensing data acquisition},
  journal = {Journal of Field Robotics}
}
@inproceedings{Brommer2018,
  doi = {10.1109/iros.2018.8594111},
  url = {https://doi.org/10.1109/iros.2018.8594111},
  pages = {arXiv:1810.05683},
  year  = {2018},
  month = {oct},
  publisher = {{IEEE}},
  author = {Christian Brommer and Danylo Malyuta and Daniel Hentzen and Roland Brockers},
  title = {Long-Duration Autonomy for Small Rotorcraft {UAS} Including Recharging},
  booktitle = {{IEEE}/{RSJ} International Conference on Intelligent Robots and Systems}
}
@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}
}