做了这么久的比赛,虽然已经离队了,不过还是总结一下与视觉联调的时候总结的一些小问题

前言

此篇仅做记录,对视觉算法等等涉入尚欠,想必会有很多纰漏与错误。比赛中主要的任务就是识别圆与神经网络分类,故从这两个任务进行记录。

感谢Sigmoid学弟的补充

识别圆

算法

具体使用与调参我也不懂,只是近日看学弟的代码发现六七个参数就能有比较好的效果了,微做感叹。

以下由Sigmoid所述

主要使用的算法是霍夫变换, 不用自己手搓, OpenCV 有内置的 cv2.HoughCircles, 对识别效果影响比较大的是 dpparam1param2 这三个参数, 具体的作用就不细说了, 展开说细节还挺多的, 推荐视觉组的队员看一下霍夫变换的具体技术细节(网上有很多这种文章), 对霍夫变换检测圆的调参会有很大的帮助。

主要说一下在具体任务场景中调参的原则:

  1. 固定 dp, 个人经验一般先把 dp 固定为 1, 即原图输入

  2. 固定 param2, param2的范围一般在 50-100, 一般将其设置为中位值 75

  3. 调整 param1, 在 50-150 范围内调整 param1, 调的越低越容易检测出圆。

  4. 如果 param1 降到了 50 还没有识别出圆或者效果依然不理想, 降低 param2, 重复步骤 3

  5. 一般情况下把 param1 和 param2 调整好了之后的效果就非常理想了, 如果还不理想, 就降低 dp 重复重复步骤 2 和 3

必须要注意的一个点是, 在使用cv2.HoughCircles时, 不要把 RGB 图转成的 灰度图直接作为 src 输入, 灰度图一定一定要经过滤波(我一般都是高斯滤波, 比较普适)!因为霍夫变换的原理中是要检测轮廓的, 比赛中地面铺的那种板子有很多小纹路, 板子与板子之间也有拼接的缝隙, 如果不经过滤波, 这些奇怪的轮廓不仅会影响圆的识别效果, 而且会增大巨多开销。

在我们组所参加的机器人比赛中, 霍夫变换检测圆基本已经能满足需求了, 并且它是一种传统的视觉算法, 开销相比神经网络小了很多, 所以在有限算力的平台上实现圆的识别一定要把霍夫变换检测圆作为首选来考虑, 不要为了追求更高的稳定性而去选择神经网络, 性价比不高。

标定

参考官方教程补充

这主要是需要使用相机内参矩阵计算圆心距离无人机中心水平坐标差,不过说起来,其实每次标定计算内参的时候,浮动还挺大的,上下浮动几十吧,不清楚到底是什么问题,不过用起来还可以,挺好的。以前总以为越清晰越好,现在感觉,就咱这识别任务,480p足以,糊一点还免的高斯模糊了(不是)

1.安装usb_cam包

sudo apt install ros-noetic-usb-cam

2.启动相机

roslaunch usb_cam usb_cam-test.launch

若是使用自己的笔记本(有摄像头的话),大概率需要修改/dev/video0/dev/video2或者/dev/video4,把下面的内容写入usb_cam.launch后使用roslaunch ./usb_cam.launch启动即可,或者sudo vim /opt/ros/noetic/share/usb_cam/launch/usb_cam-test.launch直接修改原launch也可以

<launch>
  <node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
    <param name="video_device" value="/dev/video0" />
    <param name="image_width" value="640" />
    <param name="image_height" value="480" />
    <param name="pixel_format" value="yuyv" />
    <param name="color_format" value="yuv422p" />
    <param name="camera_frame_id" value="usb_cam" />
    <param name="io_method" value="mmap"/>
  </node>
  <node name="image_view" pkg="image_view" type="image_view" respawn="false" output="screen">
    <remap from="image" to="/usb_cam/image_raw"/>
    <param name="autosize" value="true" />
  </node>
</launch>

3.准备标定板,我使用的是A4纸打印的,矩形的边长是0.0244m,所以是--square 0.0244

图片是9x7的格子,标定使用的是8x6个内角点,所以下面是--size 8x6

4.启动标定程序

rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.0244 image:=/usb_cam/image_raw camera:=/usb_cam

静置相机,把标定板粘贴在硬纸板/硬书上(防止弯曲),左右(x)、上下(y)、前后(size)、旋转(skew),各个距离都完善后进度条都变绿时点击CALIBRATE即可得出相机内参。

旋转需要有各个角度,俯仰、偏航的旋转,而非竖直旋转

相机内参使用

有一个坐标系的事情需要说明,相机中的坐标系是右x下y,比赛的无人机一般是把相机水平朝下放置,而ROS一般坐标系是前x左y上z,所以视觉的-x才是策略里的y,-y才是策略里的x,可能这么说有点绕,看看下面的代码会好理解的多。

# 相机内参
cx = ...
cy = ...
fx = ...
fy = ...
# 识别圆获得的像素坐标
pixel_x = ...
pixel_y = ...
# 计算策略代码中需要的圆目标xy
target_x = - (pixel_y - cy) / fy
target_y = - (pixel_x - cx) / fx

策略获得target_x、target_y后再乘以相机离地面的高度即可计算出圆的相对水平距离

YOLO

以下由Sigmoid所述

虽然人工智能大赛每年要求分类的数据集一直在变(去年是minist, 今年是 cifar100), 这些标准数据集有一个共同的特点就是分辨率很低(minist 是28x28, cifar100 是32x32)。但在训练的时候不要一味的追求输入高分辨率(比如直接放大10倍), 你可能觉得图像分辨率高了信息就多, 但是这种做法的缺陷很大, 一是源数据集量很大, 模型体量不足以让你把这样大分辨率的数据集很好的拟合上去; 二是分辨率高了以后信息量确实是多了, 但是这会导致原来两个类别但是相似的两张图片使得模型更加难以区分, 效果适得其反。根据个人经验, 放大2倍或者直接不放大的效果应该是最好的。

第二个需要注意的点是, 不要去数据集的 benchmark 上找 SOTA 来用, 据我尝试过的 cifar100 SOTA的经验来看, 这些 SOTA 为了提高测试集的准确度用了很多 trick, 从而使得预测结果的置信度最高才 0.2几并且在实际的任务场景中模型效果非常非常不理想, 因此建议不要这样做。

关于 YOLO, 听说现在都出到十几代了, 但是常用的几个版本是 v5 和 v8, v8带来的 ultralytics极大地简化了 YOLO 的训练的训练和部署, 在模型框架里 v8 移除了 v5 中一些 “冗余” 的层, 之所以加引号, 因为我们也不好说这些被移除的层到底有没有用, 视觉组的队员还是要从 v5 开始训练部署一遍的。

不得不说, 虽然 YOLO 并不是某些常用数据集的 SOTA, 但是它强大的泛化能力和简便操作使得我们今天依然将它作为比赛首选, 之前我还专门看了一下 YOLO 的数据增强的代码, 用了很多方法来增强泛化性, 使得训练出的模型在实际场景中效果表现很好。目前 v8 兼具目标检测、图像分类、图像分割等多种模型, 我们可以根据需要进行搭配或者选择。总结一句话, 不管是检测任务还是分类任务, 一定先用 YOLO 跑,YOLO 不行再寻找别的模型。

关于 YOLO v8 的使用, 直接看官网就可以, 操作巨简便, 几行代码就能训练自己的数据集。

以下由我所述

使用神经网络时的问题在于,我们的上位机使用的是NUC,用cpu硬跑yolov5能跑到10帧多,但是由于ros callback的机制原因,你可能会发现画面有非常大的延迟,详见此处

方法一

不优雅,但能用,将输入给yolo的数据控制在10Hz,因为计算一帧的时间小于0.1s,所以能比较实时的输出结果,至少没有大延迟。

方法二

使用while not rospy.is_shutdown(),目测rospy会自动开一个线程及时调用回调函数,不论while中运行的是什么,花费了多少时间,参照下面的写法即可

def imgmsg_to_cv2(img_msg):
    # ros图像转cv图像
    ...
    # 获取图像和消息的时间戳
    return image_opencv, img_msg.header.seq  

def task(img_origin):
    # 输入图片,使用模型进行推理的代码放在此处
    ...

img_ros_data = None
seq_current = None
# 这个回调函数会实时调用,来了一个消息就会调用,不会被主线程卡住,只负责更新图像变量
def image_callback(data):
    global img_ros_data, seq_current
    img_ros_data, seq_current = imgmsg_to_cv2(data)

if __name__ == "__main__":
    rospy.init_node('yolo_node', anonymous=True)
    # YoloTypeAndCoordinate 是自定义消息
    info_pub = rospy.Publisher('/yolo/detect', YoloTypeAndCoordinate, queue_size=1)
    img_pub = rospy.Publisher('/yolo/detect_img', Image, queue_size=1)
    rospy.Subscriber('/usb_cam/image_raw', Image, image_callback)

    # 获取上一次的时间戳,当时间戳相同(没有新图像发布)时不推理(不发布结果消息)
    seq_last_time = None
    while not rospy.is_shutdown():
        # img_ros_data和seq_current都不是None也就是最开始启动的时候没有图像消息时也不推理(不发布结果消息)
        if (img_ros_data or seq_current) is not None and seq_current != seq_last_time:
            seq_last_time = seq_current
            task(img_ros_data)

yolo训练过程相信视觉的朋友都会,但后续我打算补一个详细流程,方便我自己以后可能用(

降低开销

以下由Sigmoid所述

在比赛中, 开销最大的就是视觉模块, 除了上面的降低帧率来达到图像的实时处理之外, 可以从根本上降低模型的推理时间或者优化传统视觉算法的开销来解决这个问题(虽然现在还是没有优化到这个程度)。

传统视觉算法

比赛代码传统视觉算法部分开销最大的就是霍夫圆检测的开销, 直接在这给出结论 dp 越高, 开销越小; param1 越高开销越小; param2 越高开销越小。 所以在调整霍夫圆的参数时, 要同时结合上面的5个原则和这里的结论。

还有就是图像输入前的滤波处理, 这一部分也很重要, 之前做过一个实验, 没有滤波的时候检测圆比有滤波的时候慢了一倍。

其实优化传统视觉算法的提升空间很小, 在这里提这个优化传统视觉算法的原因是, 在实际的视觉任务中, 会发现传统视觉开销和模型推理开销并不是独立作用叠加的。举个简单的例子, 单独测试传统视觉的开销是 0.06s 一帧, 单独测试模型推理开销是 0.10s 一帧, 但是把这两个模块集成起来你会发现可能会变成 0.80s 一帧, 个人感觉应该是产生了资源竞争(内存频繁的置换)导致了这种现象的出现。但是如果把传统视觉开销优化到 0.03s 一帧, 你会发现两个模块集成起来的开销就成了 0.13s 一帧 。

在实际的任务中, 优化传统视觉算法有时候会带来意想不到的效果。

神经网络模型

这部分有很多学问, 最直接的就是优化模型网络结构, 减少参数量, 会显著提高推理速度。v8 的目标检测模型有 n/s/m/l, 模型复杂程度依次增大, 在我们比赛的任务中, 其实 n 和 s 就已经够用了。

此外, 还有很多提高推理速度的方法, 比如 C++ 和 TensorRT 部署模型加速推理, 进行量化处理等等, 记得在先进视觉比赛用过 TensorRT 部署, 但是模型转化后的识别效果直接砍了一半, 也可能是部署做法上有些细节没做到位, 值得研究的内容。

题外话

ros如何在a功能包中使用b功能包定义的数据类型

比如视觉自定义了一个消息类型传输结果内容,策略如何导入这个消息,以前一直在用../../什么的,当文件夹位置变化时需要修改,比较麻烦,建议用下面的方法,还可以防止catkin_make多线程编译报错

1.在自己的功能包的 CMakeLists.txt添加对b包的依赖

find_package(catkin REQUIRED COMPONENTS
  roscpp
  rospy
  std_msgs
  b_package
)

2.在 package.xml 文件中添加对 b包的依赖。

<depend>b_package</depend>

3.导入头文件

#include <b_package/YourMessageType.h>
from b_package.msg import YourMessageType