如何操纵一台智能车
🏎️

如何操纵一台智能车

Categories
Robot
Text
大学时参加了智能车竞赛,曾在一个月内从零开始学习并参加比赛。当时为了应付比赛非常匆忙,一年后写下此篇总结。
Date
May 18, 2024

睿抗机器人开发者大赛

项目是基于ROS操作系统来操纵智能车完成赛道上各个路段的任务。
智能车是赛题组提供的机器车,内部装有Ubuntu系统和机器人操作系统ROS
任务包括:沿着地面黑线行驶、识别沿途标识物上的火灾标识,还有统计沿途不同色系人偶个数。
沿着黑线行驶所用的方案主要基于图像处理技术,智能车前端装有一个单目相机,相机对准前方地面。我设计了一个节点来处理单目相机返回的图片,将图片从RGB空间转化为Lab色彩空间后,将原图像中黑色区域保留,其余区域变为白色,通过图像的矩来计算黑色像素的质心横坐标,将其与图片中央横坐标做差即可得到黑线偏离智能车中心轴的数值,根据此数值决定智能车的角速度正负与大小。而智能车的线速度则保持匀速。将角速度与线速度发送给底盘控制节点后即可让智能车沿着黑线行驶。
沿途标识物火灾识别具体来说是在赛道两旁竖直放着一张A4纸,纸顶端写着某某大厦四个字,下方是五个楼层的图片,每个楼层可能会贴有火焰贴纸,任务是在终端输出某某大厦几层楼有火灾。我使用了百度推出的PPYOLO训练了目标检测模型,可以检测出楼层与火焰贴纸,通过计算火焰中心与与楼层中心的纵坐标来得知火焰在几楼,在五个楼层都检测出的情况下,距离火焰中心最近的楼层即为发生火灾楼层。我还使用了PPOCR这个库来识别A4纸顶端的大厦名称
统计人偶个数这个任务的要求是在终端输出不同色系人偶的个数,有红蓝白三色系人偶,我依旧是使用了PPYOLO训练了一个目标检测模型,可以识别出不同色系人偶。
以上的火焰识别和人偶识别都是用我自己制作的数据集训练的,我准备了材料,制作了在不同灯光、背景下的各种图片作为数据集。
The project is based on the ROS operating system to control the smart car to complete tasks on various sections of the track.
The smart car is a robotic vehicle provided by the competition team, equipped with an Ubuntu system and the Robot Operating System (ROS) internally.
The tasks include: driving along the black line on the ground, identifying fire signs on the way, and counting the number of dolls in different color systems.
The scheme for driving along the black line is mainly based on image processing technology. The front of the smart car is equipped with a monocular camera, which is aimed at the ground ahead. I designed a node to process the images returned by the monocular camera. After transforming the image from the RGB color space to the Lab color space, the black areas in the original image are retained, and the rest of the areas are turned white. By calculating the centroid of the black pixels through the moments of the image, and then finding the difference between this centroid and the central horizontal coordinate of the image, we can determine the deviation of the black line from the center axis of the smart car. Based on this value, we decide the sign and magnitude of the angular velocity of the smart car. The linear velocity of the smart car is kept constant. By sending the angular velocity and linear velocity to the chassis control node, the smart car can drive along the black line.
The specific task of identifying fire signs along the way is to place a vertical A4 paper on both sides of the track, with the top of the paper marked with the words "XX Building," and below it are pictures of five floors, each of which may have a flame sticker attached. The task is to output on the terminal which floor of XX Building has a fire. I used the PPYOLO released by Baidu to train a target detection model, which can detect floors and flame stickers. By calculating the vertical coordinates of the flame center and the floor center, we can determine which floor the flame is on. If flames are detected on all five floors, the floor closest to the flame center is the one with the fire. I also used the PPOCR library to recognize the building name at the top of the A4 paper.
The task of counting the number of dolls requires outputting the number of dolls in different color systems on the terminal, with red, blue, and white dolls. I still used PPYOLO to train a target detection model that can recognize dolls of different colors.
Both the flame recognition and doll recognition were trained with my own dataset, which I prepared materials for, and made various images in different lighting and backgrounds as the dataset.

智能车

我所使用的是一台配有一个主板的智能车,说是一个智能车,其实我拿它当一个Ubuntu服务器来使用。对于车的动力部分我完全不知道细节,只知道通过向底盘控制节点发送消息(线速度与角速度)就可以控制车行动了。

在操纵智能车之前

在正式研究比赛任务之前花了很多时间来配置车的环境。包括如何让自己的笔记本电脑连接上车、conda环境的配置(因为主要使用python)。尤其是车网络的配置,对于计算机网络实际操作一无所知的我花了大量时间进行试错。但这也为我以后自己折腾开发板与主机积累了经验。
那么关于网络,当你有多个设备时,如何让各个设备相互ping通呢?
notion image
原理其实很简单,首先你需要有一个路由器,路由器设置好网关。然后让你的设备连接上路由器,一般来说会自动分配ip地址,只要你知道了某个设备的ip,就可以ping通那个设备了,比如我想要笔记本电脑ping通智能车,就需要智能车和笔记本电脑都连上同一个路由器,笔记本电脑就可以ping通智能车了,然后可以使用MobaXtern等软件操纵智能车了。
如果只是单纯地想让两台固定设备ping通(而不是像智能车这样需要不断移动),只需要用一根网线将两台设备连接就好。

ROS

整个比赛的核心是对ROS的学习。但我对ROS的编程只局限在Python,如何通过ros库来实现节点的创建、消息的通讯是最基础的东西。

ROS基础概念

工作空间

工作空间(workspace)是一个用于存放工程开发相关文件的文件夹。目前,ROS默认使用的是Catkin编译系统(在CMake的基础上拓展得到的,将 cmake 与 make 指令做了一个封装从而完成整个编译过程)。在Catkin编译系统下,一个典型的工作空间一般包含四个目录空间srcdevelbuildinstall,结构如下
workspace_folder/ |—— src/ |—— CMakeLists.txt |—— package_1/ |—— CMakeLists.txt |—— package.xml |—— ...... |—— package_2/ |—— CMakeLists.txt |—— package.xml |—— ...... |—— devel/ |—— setup.bash |—— ...... |—— build/ |—— ...... |—— install/
  1. src: 代码空间(Source Space),最常用、最重要的文件夹,用来存储所有ROS功能包(package)的源文件
  1. build: 编译空间(Build Space),catkin_make命令自动生成,用来存储工作空间编译过程中产生的缓存信息和中间文件。
  1. devel: 开发空间(Development Space),catkin_make命令自动生成,用来放置编译生成的可执行文件
  1. install: 安装空间(Install Space),不是必需的,很多工作空间没有该文件夹。编译成功后,可以使用make install命令将可执行文件安装到该空间中,运行该空间中的环境变量脚本,即可在终端中运行这些可执行文件。
工作空间并不是整个ROS开发所在的空间,不同的项目可以有各自的工作空间,只需要配置各自的环境变量即可(source devel/setup.bash)。

功能包

功能包(package)是ROS中的基本单元,包含ROS节点、库、配置文件等。
多个功能包平行放置在代码空间(src)中

智能车的整体架构

行驶模式控制节点
单独运行一个节点检查前方是否有黑线,有则运行巡线节点,无则运行雷达节点
rospy.init_node('vel_controller')
巡线节点
# ROS节点初始化 rospy.init_node('linetrack', anonymous=True) # 创建速度话题 cmd_vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
雷达节点
rospy.init_node('lidar_follower') self.laser_sub = rospy.Subscriber('/scan', LaserScan, self.laser_callback) self.cmd_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10)
 

如何让智能车沿着黑线行驶

使用设备:单目相机
算法内容:
  1. 将图像从RGB色彩空间转换为Lab色彩空间(原因:因为比赛场馆使用的是暖色光,且光线较暗,原本备赛时使用的是RGB色彩空间,在比赛场地试运行时发现受灯光的影响很大,所以修改成了Lab色彩空间,因为Lab色彩空间的亮度对比更加明显,更能突出黑色线与白色背景图的区别)
  1. 设定一个范围,在这个范围之内的颜色转为黑色,范围之外的颜色变为白色,生成一个二值掩膜图像
  1. 通过使用掩膜图像的矩来计算黑色像素点的质心所在的位置 m['m00']:零阶矩,用于描述图像的总体亮度或面积。 m['m10']、m['m01']:一阶矩,描述图像的质心、平均位置和分布,通常用于计算图像的中心位置
  1. 计算图像质心和图像中心的像素差
  1. 确定一个超参数,实现由像素差到角速度的转换
cap = cv2.VideoCapture(1) # 读取图像帧 ret, cv_image = cap.read() # 对图像进行裁剪 height, width, channels = cv_image.shape descentre = 0 rows_to_watch = 100 crop_img = cv_image[(height)//2 + descentre:(height)//2 + (descentre + rows_to_watch)][10:width-10] # 将图像从RGB转换为Lab色彩空间 lab = cv2.cvtColor(crop_img, cv2.COLOR_RGB2Lab) # 设置需要提取的颜色为黑色,然后确认其Lab空间下的范围 lower_black = np.array([0, 0, 0]) upper_black = np.array([100, 128, 128]) # 制作模板,黑色部分和其他颜色二值化后变为白色和黑色 mask = cv2.inRange(lab, lower_black, upper_black) m = cv2.moments(mask, False) try: cx, cy = m['m10'] / m['m00'], m['m01'] / m['m00'] except ZeroDivisionError: cx, cy = (width-20) / 2, 0 error_x = cx - width / 2 twist_object = Twist() twist_object.linear.x = 0.25 twist_object.angular.z = -error_x / 300 # 如何确定像素差值与角速度之间的比例 # 如何让线速度与角速度匹配?实验 no_red = cv2.countNonZero(mask) if ((math.fabs(twist_object.angular.z)) <2): cmd_vel_pub.publish(twist_object) rospy.loginfo("ANGULAR VALUE SENT ===>" + str(twist_object.angular.z)) else: twist_object.linear.x = 0 rospy.loginfo("Out of range Stop!!! " + str(twist_object.angular.z)) twist_object.angular.z = 0 cmd_vel_pub.publish(twist_object)

如何让智能车雷达避障

 
class FenceFollower: def __init__(self): rospy.init_node('fence_follower') self.laser_sub = rospy.Subscriber('/scan', LaserScan, self.laser_callback) self.cmd_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=10) self.rate = rospy.Rate(10) def laser_callback(self, scan): L_distances=0 R_distances=0 for i in scan.ranges[650:700]: L_distances=L_distances+i for i in scan.ranges[200:250]: R_distances=R_distances+i L_distances=L_distances/50 R_distances=R_distances/50 fence_distance = (L_distances+R_distances)/2 if L_distances > fence_distance+0.03 : vel_cmd = Twist() vel_cmd.linear.x = 0.05 vel_cmd.angular.z = 0.18 rospy.loginfo("DISTANCE VALUE SENT ===>" + str(L_distances)+' '+str(fence_distance)) elif L_distances < fence_distance-0.01: vel_cmd = Twist() vel_cmd.linear.x = 0.05 vel_cmd.angular.z = -0.18 rospy.loginfo("DISTANCE VALUE SENT ===>" + str(L_distances)+' '+str(fence_distance)) else: vel_cmd = Twist() vel_cmd.linear.x = 0.2 rospy.loginfo("DISTANCE VALUE SENT ===>" + str(L_distances)+' '+str(fence_distance)) self.cmd_pub.publish(vel_cmd) def run(self): while not rospy.is_shutdown(): self.rate.sleep()

火灾检测

自己制作数据集,进行标注,然后训练模型

实际困难与解决方法

场馆光线问题:将RGB转换为Lab色彩空间