Skip to content

颜色识别及巡线

Yuhua edited this page Aug 11, 2020 · 1 revision

颜色识别及巡线

本教程的目的:

  • 理解颜色识别程序背后的原理
  • 掌握颜色识别程序,并能够进行二次开发
  • 掌握巡线程序,并能够进行二次开发

识别算法介绍

  • 订阅:

真实环境中订阅的相机话题为/prometheus/camera/rgb/image_raw

仿真环境中订阅的相机话题为/P300_Monocular_front/Monocular/image_raw

  • 发布:

检测结果话题/prometheus/object_detection/color_line_angle

消息类型geometry_msgs.msg.Pose

Pose.x 为检测到的误差角度,Pose.y 为检测标志位(1代表正常检测,-1代表未检测到)

  • 配置文件

真实环境中的配置文件为Prometheus/Modules/object_detection/config/camera_param.yaml

仿真环境中的配置文件为Prometheus/Modules/object_detection/config/camera_param_gazebo_monocular.yaml

  • launch参数

线距底边的距离,0-1,0.5表示在图像中间

   <param name="line_location" value="0.5"/>
   <param name="line_location_a1" value="0.3"/>
   <param name="line_location_a2" value="0.7"/>

待检测颜色,没有此颜色时,默认检测黑色,可选:black,red,yellow,green,blue

   <param name="line_color" value="black"/>
  • 颜色检测算法介绍

目前在计算机视觉领域存在着较多类型的颜色空间(color space)。HSL和HSV是两种最常见的圆柱坐标表示的颜色模型,它重新影射了RGB模型,从而能够视觉上比RGB模型更具有视觉直观性。

GhWljA.jpg

颜色分割实现代码:

inRange(imgHSV, Scalar(iLowH, iLowS, iLowV), Scalar(iHighH, iHighS, iHighV), imgThresholded); //Threshold the image

HSV颜色查询表

GhWtN8.jpg

巡线算法介绍

color_line_following.cpp

  • 订阅线条识别结果,即在相机视野中的夹角

      ros::Subscriber vision_sub = nh.subscribe<std_msgs::Float32>("/prometheus/object_detection/color_line_angle", 10, vision_cb);
    
  • 发布上层控制指令

      ros::Publisher command_pub = nh.advertise<prometheus_msgs::ControlCommand>("/prometheus/control_command", 10);
    
  • 控制策略说明

    • 高度不变,与起飞高度平齐
    • xy方向采用机体系xy速度控制,可通过参数设置x轴前进速度,y轴速度根据与线偏差量计算得到
    • 偏航角根据线在视场中的斜率计算得到,同样是采用机体系增量式控制

仿真流程

  • 运行启动脚本(注意选择颜色及其他相关参数设置) roslaunch prometheus_gazebo sitl_color_line_following.launch G2OMqJ.md.png
  • 输入1,飞机将起飞至预设点,可在终端中查看相关信息 G2OKr4.md.png
  • 等待一段时间后,飞机将执行巡线任务 G2OlZ9.md.png

运行截图 GOkLi8.gif

如何进行真机实验?

相机购买

相机标定

# 首先启动相机节点,如下命令启动相机ID=0
roslaunch prometheus_detection web_cam0.launch
# 然后利用ros自带的标定程序对相机进行标定
rosrun camera_calibration cameracalibrator.py --size 8x6 --square 0.0245 image:=/prometheus/camera/rgb/image_raw
  • 其中:size为标点板尺寸,square为每个方格宽度(m),image:=相机话题

  • 棋盘格标定板下载地址:Chessboard

  • 将得到的参数写入如下文件(有关目标尺度的预定义也在这个文件中):Prometheus/Modules/object_detection/config/camera_param.yaml,例如参数如下:

  • 标定板样张如下

巡线道具购买

运行代码

## 请根据自己的相机节点选择
roslaunch prometheus_detection web_cam0.launch
## 巡黑线
roslaunch prometheus_detection color_det.launch
## 巡蓝线
roslaunch prometheus_detection color_det_blue.launch
## 巡红线
roslaunch prometheus_detection color_det_red.launch

相对于相机中心的偏移角精度测试

可以看出平均误差在6-degree左右,可能存在标定偏移。

线宽为0.06m时,最高的检测距离为0.7m,最低检测距离为0.1m

实际测试视频

video1

Clone this wiki locally