写在前面:
🌟 欢迎光临 清流君 的博客小天地,这里是我分享技术与心得的温馨角落。📝

个人主页清流君_CSDN博客,期待与您一同探索 移动机器人 领域的无限可能。

🔍 本文系 清流君 原创之作,荣幸在CSDN首发🐒
若您觉得内容有价值,还请评论告知一声,以便更多人受益。
转载请注明出处,尊重原创,从我做起。

👍 点赞、评论、收藏,三连走一波,让我们一起养成好习惯😜
在这里,您将收获的不只是技术干货,还有思维的火花

📚 系列专栏:【机器视觉】系列,带您深入浅出,领略控制之美。🖊
愿我的分享能为您带来启迪,如有不足,敬请指正,让我们共同学习,交流进步!

🎭 人生如戏,我们并非能选择舞台和剧本,但我们可以选择如何演绎 🌟
感谢您的支持与关注,让我们一起在知识的海洋中砥砺前行~~~



引言

  博主在前面的文章介绍了使用 usb_cam 驱动运行 Apriltag 算法,但采集得到的数据频率太低,只有 4 H z 4Hz 4Hz ,无法与 50 H z 50Hz 50HzUWB 定位数据做融合处理。因此,本篇博客的目的是提高 Apriltag 识别算法的检测频率到 20 H z 20Hz 20Hz 以满足与 50 H z 50Hz 50HzUWB 定位数据融合处理的需求。

  本篇博客是博主解决问题的日志记录。

  当前 AprilTag 算法检测频率为 4 H z 4Hz 4Hz,要提高到 20 H z 20Hz 20Hz 左右。


一、查看话题发布频率

通过rostopic hz命令查看相关话题的发布频率

rostopic hz [options] /topic_0 [/topic_1 [topic_2 [..]]]

1.1 查看算法检测频率

首先要查看的是 Apriltag 标签的检测频率。

rostopic hz \tag_detections

得到结果:

subscribed to [ /tag_detections ]
average rate: 9.163
min: 0.108s max: 0.112s std dev: 0.00174s window: 5
average rate: 9.198
min: 0.105s max: 0.112s std dev: 0.00211s window: 14
average rate: 9.224
min: 0.105s max: 0.112s std dev: 0.00178s window: 23

实测话题发布频率为 9 H z 9 Hz 9Hz 左右。

同时识别标签的个数与算法识别的速度有关,即:

  • 当同时识别 4 4 4 个标签时,记录数据的频率约为 4 H z 4Hz 4Hz

  • 当只识别 1 1 1 个标签时,记录数据的频率约为 6 H z 6Hz 6Hz

因此可得, Apriltag 检测频率和算法处理的复杂度有关。

1.2 查看相机帧率

  博主是用的是usb_cam相机驱动,查看相机帧率

  💡 usb_cam 驱动通常会发布一个包含图像的 ROS 话题。可以使用 rostopic hz 命令来查看该话题的发布频率,这大致等同于相机的帧率。

rostopic hz /usb_cam/image_raw

得到结果:

subscribed to [ /usb_cam/image_raw ]
average rate: 24.644
min: 0.039s max: 0.045s std dev: 0.00182s window: 12

相机帧率约为 24 H z 24Hz 24Hz

如何让记录到的数据也差不多为 20 H z 20Hz 20Hz 呢?


二、启动Apriltag识别算法指令

2.1 刷新环境变量

source ~/ros_ws/devel/setup.bash

2.2 启动 USB 相机驱动

roslaunch usb_cam usb_cam-test.launch

2.3 运行 AprilTag_ros 算法

roslaunch apriltags2_ros continuous_detection.launch

三、问题排查

3.1 排查订阅频率问题

  目前订阅检测 AprilTag 识别算法发布的话题,没有关于 Rate 的设置,意思就是只要发布了就立即订阅,那么问题就不在订阅方

  相机的帧率是 20 H z 20Hz 20Hz ,这是硬件上限,但是识别 Apriltag 的算法得到的定位数据能达到 20 H z 20Hz 20Hz 嘛,博主这里实测是每秒记录 4 4 4 ~ 6 6 6 条数据。

那么能否提高算法识别 Apriltag 标签的频率?

3.2 排查相机帧率问题

  现在尝试提高相机帧率,更换双目摄像头,测试相机帧率为 30 H z 30Hz 30Hz

查看相机帧率:

rostopic hz /usb_cam/image_raw

得到结果:

subscribed to [ /usb_cam/image_raw ] average rate: 30.064
min: 0.030s max: 0.037s std dev: 0.00221s window: 15

测试识别算法频率仍然为 4 H z 4Hz 4Hz

rostopic hz /tag_detections

average rate: 4.443
min: 0.225s max: 0.225s std dev: 0.00000s window: 2

说明不是摄像头的问题,而是算法的问题。


四、Apriltag 算法配置问题

4.1 配置文件

settings.yaml 文件内容如下:

# AprilTags 2 code parameters
# Find descriptions in apriltags2/include/apriltag.h:struct apriltag_detector
#                      apriltags2/include/apriltag.h:struct apriltag_family
tag_family:        'tag36h11' # options: tag36h11, tag36h10, tag25h9, tag25h7, tag16h5
tag_border:        1          # default: 1
tag_threads:       2          # default: 2
tag_decimate:      1.0        # default: 1.0
tag_blur:          0.0        # default: 0.0
tag_refine_edges:  1          # default: 1
tag_refine_decode: 0          # default: 0
tag_refine_pose:   0          # default: 0
tag_debug:         0          # default: 0
# Other parameters
publish_tf:        false       # default: false

4.2 各项解释

(1) AprilTags检测算法参数

  • tag_family: 指定标签的种类。 AprilTags 有多种不同的标签家族,每个家族都有不同的尺寸和错误纠正能力。可选项包括:

    • tag36h11: 36 36 36 位, 11 11 11 位纠错,适用于大范围和高噪声环境。
    • tag36h10: 36 36 36 位, 10 10 10 位纠错。
    • tag25h9: 25 25 25 位, 9 9 9 位纠错。
    • tag25h7: 25 25 25 位, 7 7 7 位纠错。
    • tag16h5: 16 16 16 位, 5 5 5 位纠错,适用于小尺寸和低噪声环境。
  • tag_border: 标签周围是否有边界(通常为黑色)。设置为 1 1 1 表示有边界,设置为 0 0 0 表示无边界的 AprilTag

  • tag_threads: 检测时使用的线程数。增加线程数可以提高检测速度,但也会增加 CPU 的使用率。

  • tag_decimate: 图像降采样率。这个参数可以加快检测速度,但可能会降低精度。值为 1.0 1. 0 1.0 表示不降采样。

  • tag_blur: 高斯模糊的σ值。对图像进行预处理模糊可以减少高频噪声,但过度的模糊可能会降低检测精度。

  • tag_refine_edges: 是否细化边缘。设置为 1 1 1 时,会尝试优化边缘检测以提高精度。

  • tag_refine_decode: 是否细化解码。细化解码可以改善解码过程,但可能会稍微增加计算时间。

  • tag_refine_pose: 是否细化位姿估计。细化位姿估计可以提供更精确的位姿数据。

  • tag_debug: 是否启用调试模式。调试模式通常用于开发者,以输出额外的调试信息。

(2) 其他参数

  • publish_tf: 是否发布 TF 变换。在 ROSRobot Operating System )等系统中, TF 用于表示坐标变换。如果设置为 true ,则 AprilTags 检测器将发布检测到的标签的坐标变换。

  提高检测时使用的线程数 tag_threads 的值通常可以增加每秒识别的图像数量,因为这样可以并行处理多个图像或者图像的多个部分,从而加快整体的处理速度。每个线程可以独立地执行 AprilTags 检测算法,因此使用更多的线程可以在多核处理器上实现更高效的利用


五、最终解决方案

5.1 提高线程数

下面尝试检测时使用的线程数,由 2 2 2 提高为 3 3 3

tag_threads:    3      # default: 2

查看算法检测频率:

rostopic hz /tag_detections

得到结果:

subscribed to [ /tag_detections ]
average rate: 6.066
min: 0.156s max: 0.170s std dev: 0.00554s window: 7

线程数修改为 3 3 3 ,频率由 4 H z 4Hz 4Hz 变为了 6 H z 6Hz 6Hz ,确实有提高!

  • 继续提高为 4 4 4 ,仍为 6 H z 6Hz 6Hz

  • 继续提高为 5 5 5 ,仍为 6 H z 6Hz 6Hz

可见继续提高也不变了检测频率

5.2 修改图像降采样率

下面改变图像降采样率为 2.0 2 . 0 2.0 ,有奇效!

tag_decimate:    2.0     # default: 1.0

查看 Apriltag 算法检测频率

rostopic hz /tag_detections

subscribed to [ /tag_detections ]
average rate: 26.164

采样频率达到了 26 H z 26Hz 26Hz

简单看看定位精度,还可以接受。

采样频率成功提高,若想要达到正好的 20 H z 20Hz 20Hz ,需要试凑图像降采样率tag_decimate

  • 将其改为 1.9 1 . 9 1.9 时,频率降为了 6 H z 6Hz 6Hz 左右
  • 将其改为 2.1 2 . 1 2.1 时,频率差不多为 25 H z 25Hz 25Hz 左右

所以就用 2.0 2 . 0 2.0 ,得到 25 H z 25Hz 25Hz 的采样频率就好。

完整的settings.yaml文件内容如下:

# AprilTags 2 code parameters
# Find descriptions in apriltags2/include/apriltag.h:struct apriltag_detector
#                      apriltags2/include/apriltag.h:struct apriltag_family
tag_family:        'tag36h11' # options: tag36h11, tag36h10, tag25h9, tag25h7, tag16h5
tag_border:        1          # default: 1
tag_threads:       4          # default: 2
tag_decimate:      2.0        # default: 1.0
tag_blur:          0.0        # default: 0.0
tag_refine_edges:  1          # default: 1
tag_refine_decode: 0          # default: 0
tag_refine_pose:   0          # default: 0
tag_debug:         0          # default: 0
# Other parameters
publish_tf:        false       # default: false

六、总结

  修改~/ros_ws/src/Apriltags2_VO/apriltags2_ros/config路径下的settings.yaml文件中的以下两项参数:

  • 降采样率参数 tag_decimate 修改为 2.0 2 . 0 2.0
  • 检测时使用的线程数 tag_threads 修改为 4 4 4

可将 Apriltag 识别算法的检测频率由 4 H z 4Hz 4Hz 提高到 25 H z 25Hz 25Hz 左右。


参考资料

   ZED - Mini 标定完全指南(应该是最详细的吧)


后记:

🌟 感谢您耐心阅读这篇关于 Apriltag 识别算法提高检测频率 的技术博客。 📚

🎯 如果您觉得这篇博客对您有所帮助,请不要吝啬您的点赞和评论 📢

🌟您的支持是我继续创作的动力。同时,别忘了收藏本篇博客,以便日后随时查阅。🚀

🚗 让我们一起期待更多的技术分享,共同探索移动机器人的无限可能!💡

🎭感谢您的支持与关注,让我们一起在知识的海洋中砥砺前行 🚀

Logo

助力广东及东莞地区开发者,代码托管、在线学习与竞赛、技术交流与分享、资源共享、职业发展,成为松山湖开发者首选的工作与学习平台

更多推荐