本文记录一次基于 ROS 2 Humble 的apriltag_ros快速实验生成 AprilTag 标定板回放 RealSense rosbag2 数据集启动 AprilTag 检测节点并在 RViz 中查看检测结果和 TF。项目环境OSUbuntu 22.04虚拟机VirtualBox 7.0ROSROS 2 Humble目录0. apriltag_ros 概述1. 安装依赖2. 准备数据集3. 实验3.1 生成 AprilTag 标定板3.2 回放数据并检测4. 验证结果5. 参数说明5.1 Launch 参数5.2 YAML 结构5.3 基础参数5.4 Detector 调参5.5 指定 tag ID、frame 和尺寸6. 常见问题参考0. apriltag_ros 概述AprilTag 是一种视觉基准标记系统最早由 University of Michigan APRIL Lab 提出并在 2011 年 ICRA 论文AprilTag: A robust and flexible visual fiducial system中系统介绍。它把类似二维码的黑白标签放到环境或物体上让机器人只通过一帧相机图像就能识别 tag ID并结合相机内参估计 tag 相对相机的 6D 位姿。图1 Applications and users of AprilTags来自AprilTag 2: Efficient and robust fiducial detection。apriltag_ros是 AprilTag 检测库的 ROS 2 节点封装。它订阅图像和CameraInfo检测画面中的 AprilTag然后发布 tag 的 ID、位姿、检测质量信息以及标准 ROS TF。这样后续节点不需要直接处理图像算法只要订阅/detections或读取/tf就可以把 tag 用在定位、标定、导航、抓取、数据集验证等任务里。本次实验用二进制安装的apriltag_ros做 AprilTag 检测利用从 Intel RealSense 采集的 rosbag2 数据集回放测试。仓库包含以下内容launch/detector.launch.py启动上游apriltag_ros/apriltag_node并把相机话题、参数文件、输出话题做成 launch 参数。config/tags_36h11.yaml默认使用tag36h11标签边长按0.045 m配置。launch/display.launch.py启动 RViz并加载rviz/tag_rivz.rviz。上游apriltag_ros节点订阅 rectified image 和CameraInfo发布/tf与apriltag_msgs/msg/AprilTagDetectionArray。1. 安装依赖以 ROS 2 Humble 为例先 source ROS 2 环境source/opt/ros/humble/setup.bash安装上游包sudoaptupdatesudoaptinstallros-$ROS_DISTRO-apriltag-ros如果需要重新生成本文使用的 AprilTag 标定板还需要 Python 依赖pip3installopencv-python numpy reportlab在工作空间根目录构建本 quick startmkdir~/ros2_wscd~/ros2_wsgitclone https://gitee.com/jay-tan/robot_mini_projects.gitcdrobot_mini_projects rosdepinstall--from-paths src --ignore-src-r-ycolcon build --symlink-install --packages-select apriltag_ros_quickstartsourceinstall/setup.bash2. 准备数据集本项目按 RealSense 采集的数据集下载链接: https://pan.baidu.com/s/1zePQvusOq-OXeCjO2MszWA?pwd1024来测试, RealSense ROS 2 话题如下/camera/camera/color/image_raw - sensor_msgs/msg/Image /camera/camera/color/camera_info - sensor_msgs/msg/CameraInfoapriltag_ros需要图像和CameraInfo的时间戳匹配camera_info里的相机内参会用于计算 tag pose。拿到数据集后先检查 bag 里是否包含这两个话题ros2 bag infoyour_realsense_bag如果你的数据集话题名不同后面启动detector.launch.py时把image_topic和camera_info_topic改成实际话题即可。3. 实验3.1 生成 AprilTag 标定板tools/april_tag_board.py可以生成一张适合 A4 打印的tag36h11AprilTag 标定板。脚本默认生成 3 行 3 列tag ID 为0到8每个 tag 下方带有对应 ID 标注。运行脚本cd~/ros2_ws/robot_mini_projects/src/01_apriltag_ros python3 tools/april_tag_board.py脚本会在当前目录生成apriltag_board_A4.pdf apriltag_board_tmp.png本仓库已经把生成好的文件放在doc/目录中doc/apriltag_board_A4.pdf doc/apriltag_board_tmp.png实际实验时建议打印doc/apriltag_board_A4.pdf并保持打印比例为 100%。如果修改了脚本里的tag_size、gap、rows、cols等参数需要同步检查config/tags_36h11.yaml中每个 tag 的尺寸配置保证检测节点使用的物理尺寸和实际打印尺寸一致。3.2 回放数据并检测建议开三个终端一个回放 RealSense 数据集一个启动 AprilTag 检测一个启动 RViz。终端一回放数据集# 循环播放ros2 bag play rosbag2_2026_05_05-20_41_42_0.db3-l--clock本文示例数据集文件名为rosbag2_2026_05_05-20_41_42_0.db3如果使用自己的数据集请替换为实际 rosbag2 路径。终端二启动检测节点ros2 launch apriltag_ros_quickstart detector.launch.py\image_topic:/camera/camera/color/image_raw\camera_info_topic:/camera/camera/color/camera_info终端三启动 RViz。回放 bag 时建议打开仿真时间ros2 launch apriltag_ros_quickstart display.launch.py use_sim_time:true如果直接接 RealSense 相机实时运行而不是回放 bagRViz 可以保持默认ros2 launch apriltag_ros_quickstart display.launch.py4. 验证结果查看检测数组ros2 topicecho/detections查看 TF。默认 frame 名形如tag36h11:idros2 run tf2_ros tf2_echo camera_color_opuical_frame tag36h11:0图2 运行效果图。5. 参数说明这个 quick start 有两层参数launch 参数控制本 demo 如何把话题和配置文件传给上游节点。apriltag_ros参数写在config/tags_36h11.yaml控制 AprilTag 检测行为。5.1 Launch 参数detector.launch.py参数参数默认值说明image_topic/camera/image_rect输入图像话题对应上游节点内部的image_rect订阅。RealSense 数据集通常覆盖为/camera/camera/color/image_raw。camera_info_topic/camera/camera_info相机内参话题。时间戳需要和图像消息匹配位姿估计会使用其中的投影矩阵RealSense 数据集通常覆盖为/camera/camera/color/camera_info。detections_topic/detectionsAprilTag 检测结果输出话题。消息类型是apriltag_msgs/msg/AprilTagDetectionArray。configconfig/tags_36h11.yaml传给apriltag_ros的 YAML 参数文件路径。换 tag family、尺寸、检测参数时通常改这个文件。display.launch.py参数参数默认值说明use_sim_timefalseRViz 是否使用/clock。回放 rosbag2 数据集并使用ros2 bag play --clock时设为true。5.2 YAML 结构config/tags_36h11.yaml的顶层 key 是apriltagapriltag:ros__parameters:family:36h11size:0.045这个名字要和 launch 文件中启动的节点名一致。本 demo 里节点名是apriltagNode(packageapriltag_ros,executableapriltag_node,nameapriltag,)如果以后把节点名改成tag_detectorYAML 顶层也要对应改成tag_detector否则参数不会加载到目标节点。5.3 基础参数参数类型本 demo 默认值说明image_transportstringraw图像传输方式。raw订阅普通sensor_msgs/msg/Imagecompressed会使用压缩图像传输。先用raw跑通确认带宽有压力时再考虑压缩。familystring36h11Tag family。实际使用的标签必须和这里一致否则不会被当前 detector 识别。常用36h11官方还支持16h5、25h9、Circle21h7、Circle49h12、Custom48h12、Standard41h12、Standard52h13。sizefloat0.045默认 tag 边长单位米。这里指黑白 tag 外边框的真实边长会直接影响/tf里的距离尺度。profileboolfalse是否输出性能 profiling 信息。调性能时打开正常 demo 保持关闭。max_hammingint2允许的最大纠错位数。0最严格、误检少1或2更宽松但复杂画面里误检风险更高。pose_estimation_methodstringpnp位姿估计方法。本 quick start 使用pnp。改这个参数前建议先确认当前安装版本支持的取值。size是最容易影响结果的参数。只看 2D 检测时它不太敏感但做定位、抓取、相机外参验证时必须量准图3中红色箭头即不同 tag 的尺寸位置。图3 AprilTag size 示意。这里的size不是整张纸的宽度也不是白色留边后的外框尺寸而是 AprilTag 图案本身的边长从黑色外边框的一侧量到另一侧。实际使用前建议用尺子量打印后的实物尺寸并把米制数值写入配置例如 4.5 cm 对应0.045。5.4 Detector 调参这些参数位于 YAML 的detector下detector:threads:2decimate:1.0blur:0.0refine:truesharpening:0.25debug:false参数类型本 demo 默认值调参方向detector.threadsint2检测线程数。提高后可能增加吞吐但会占更多 CPU小主机上不要盲目设太大。detector.decimatefloat1.0检测前对图像降采样。数值越大速度越快但远处或画面里很小的 tag 更容易漏检RealSense 数据集回放测试默认用1.0提高稳定性。detector.blurfloat0.0quad detection 前的高斯模糊 sigma。0.0表示不模糊噪声很重时可小幅增加过大则会抹掉边缘。detector.refinebooltrue是否把 quad 边缘贴合到更强的图像梯度上。必须写成 YAML bool例如true或false。detector.sharpeningfloat0.25解码阶段的锐化强度。画面轻微虚焦时可小幅调整过高可能放大噪声。detector.debugboolfalse是否写出调试图像到当前工作目录。必须写成 YAML bool例如true或false排查检测失败时可临时打开长期运行不要打开。5.5 指定 tag ID、frame 和尺寸默认不写tag.ids时会按检测到的 tag 发布结果。想只关心指定 tag或给不同 tag 配不同 frame/尺寸可以加入tag:ids:[0,1]frames:[tag_0,tag_1]sizes:[0.162,0.120]参数类型说明tag.idsint array需要单独配置的 tag ID。tag.framesstring array每个 tag 对应的 TF child frame 名。如果为空上游会使用默认格式形如tag36h11:0。tag.sizesfloat array每个 tag 对应的实际边长单位米会覆盖全局size。ids、frames、sizes如果同时填写长度需要一致。只要不同 tag 的真实尺寸不一样就不要只依赖全局size应该给每个 ID 单独写tag.sizes。6. 常见问题1./detections没有输出怎么办先确认图像话题和相机内参话题是否正确ros2 topic list ros2 topicecho/camera/camera/color/camera_info--once然后确认画面中的 tag family 和配置文件里的family一致。例如本文使用的是tag36h11配置中应为family: 36h11。2. 能看到图像但检测不到 tag 怎么办优先检查打印质量、光照、运动模糊和 tag 在画面中的大小。远距离或 tag 很小时可以先把detector.decimate保持为1.0避免降采样导致漏检。3. 检测到了 tag但距离或位姿不准怎么办重点检查size。它必须是 AprilTag 黑白图案本身的真实边长单位是米不是整张纸的宽度也不是白色留边后的外框尺寸。打印后建议用尺子重新量一遍。4. RViz 看不到 TF 怎么办回放 rosbag2 时需要ros2 bag play加--clock并且 RViz 使用use_sim_time:true。如果实时接相机运行则 RViz 可以保持默认的use_sim_time:false。5. 公众号或 CSDN 中图片不显示怎么办Gitee README 可以直接使用仓库内的相对路径例如images/the_tag_size.png。发布到 CSDN 或微信公众号时建议把图片上传到对应平台再把 Markdown 中的图片链接替换为平台生成的图片地址。参考apriltag_ros官方文档https://docs.ros.org/en/ros2_packages/humble/api/apriltag_ros/apriltag_rosROS Indexhttps://index.ros.org/p/apriltag_ros/apriltag_msgsROS Indexhttps://index.ros.org/p/apriltag_msgs/AprilTag 原始论文https://april.eecs.umich.edu/papers/details.php?nameolson2011tagsAprilTag 检测库文档https://docs.ros.org/en/ros2_packages/rolling/api/apriltag/index.htmlAprilTag 2: Efficient and robust fiducial detectionhttps://april.eecs.umich.edu/pdfs/wang2016iros.pdfapriltag_ros githubhttps://github.com/christianrauch/apriltag_ros