ROS2自动驾驶
yolo5自动驾驶
1、重要!更换U盘的操作指引
2、关闭开机自启动大程序
3、Linux基础
4、YoloV5训练集
5、自动驾驶基础调试(代码解析)
6、自动驾驶特调
7、自动驾驶原理
8、PID算法理论
9、阿克曼运动学分析理论
10、建立运动学模型
常用命令
!重要!首次使用
一、原理分析
麦克纳姆轮运动学分析
二、AI大模型
3、AI大模型类型和原理
4、RAG检索增强和模型训练样本
5、具身智能机器人系统架构
6、具身智能玩法核心源码解读
7、配置AI大模型
8、配置API-KEY
三、深度相机
2、颜色标定
10、深度相机的基础使用
11、深度相机伪彩色图像
12、深度相机测距
13、深度相机色块体积测算
14、深度相机颜色跟随
15、深度相机人脸跟随
16、深度相机KCF物体跟随
17、深度相机Mediapipe手势跟随
18、深度相机视觉循迹自动驾驶
19、深度相机边缘检测
四、多模态视觉理解
20、多模态语义理解、指令遵循
21、多模态视觉理解
22、多模态视觉理解+自动追踪
23、多模态视觉理解+视觉跟随
24、多模态视觉理解+视觉巡线
25、多模态视觉理解+深度相机距离问答
26、多模态视觉理解+SLAM导航
27、多模态视觉理解+SLAM导航+视觉巡线
28、意图揣测+多模态视觉理解+SLAM导航+视觉功能
五、雷达
8、雷达基础使用
思岚系列雷达
六、建立地图
9、Gmapping建图
cartographer快速重定位导航
RTAB-Map导航
RTAB-Map建图
slam-toolbox建图
cartographer建图
Navigation2多点导航避障
Navigation2单点导航避障
手机APP建图与导航
七、新机器人自动驾驶与调整
多模态视觉理解+SLAM导航
新机器人自动驾驶
场地摆放及注意事项
启动测试
识别调试
无人驾驶的车道保持
无人驾驶路标检测
无人驾驶红绿灯识别
无人驾驶之定点停车
无人驾驶转向决策
无人驾驶之喇叭鸣笛
无人驾驶减速慢行
无人驾驶限速行驶
无人驾驶自主泊车
无人驾驶综合应用
无人驾驶融合AI大模型应用
八、路网规划
路网规划导航简介
构建位姿地图
路网标注
路网规划结合沙盘地图案例
路径重规划
九、模型训练
1、数据采集
2、数据集标注
3、YOLOv11模型训练
4、模型格式转换
十、YOLOV11开发
多机通讯配置
汝城县职业中等专业学校知识库-信息中心朱老师编辑
-
+
首页
七、新机器人自动驾驶与调整
识别调试
识别调试
# 启动识别 ## 1. 课程内容 **注意:这个程序是在沙盘地图上运行的,个人地图需要自行调整程序,这个课程是调试小车识别每个路标的置信度,默认不需要修改** 基础:启动自动驾驶程序,观察路标识别结果。 ## 2.测试前准备 * 调整测试参数 参数路径:`~/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/config/yolo_param.yaml` ``` #路标检测推理参数 sign_detection: model_path: '/home/jetson/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/tools/sign_model.engine' conf: 0.92 #设置检测的最小置信度阈值。 将忽略置信度低于此阈值的检测到的对象。 调整此值有助于减少误报。 iou: 0.7 #用于非极大值抑制 (NMS) 的重叠阈值。较低的值会通过消除重叠的框来减少检测结果 rect: True #如果启用,则对图像较短的一边进行最小填充,直到可以被步长整除,以提高推理速度。 half: True #如果启用,则使用半精度推理,可以加快在支持的 GPU 上的模型推理速度,同时对准确性的影响极小。 device: "cuda:0" #推理设备 batch : 50 #批处理大小,更大的批处理大小可以提供更高的吞吐量,从而缩短推理所需的总时间。 max_det : 2 #最多检测的物体数 augment : False #启用测试时增强 (TTA) 进行预测,可能会提高检测的鲁棒性,但会降低推理速度。 verbose : False #是否在终端输出推理的详细信息。 classes : [0, 1, 2, 3, 4, 5, 6, 8, 9, 10, 11, 12, 13] line_detection: #车道线检测推理参数 model_path: '/home/jetson/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/tools/lane_V6.engine' conf: 0.5 #设置检测的最小置信度阈值。 将忽略置信度低于此阈值的检测到的对象。 调整此值有助于减少误报。 iou: 0.6 #用于非极大值抑制 (NMS) 的重叠阈值。较低的值会通过消除重叠的框来减少检测结果 rect: True #如果启用,则对图像较短的一边进行最小填充,直到可以被步长整除,以提高推理速度。 half: True #如果启用,则使用半精度推理,可以加快在支持的 GPU 上的模型推理速度,同时对准确性的影响极小。 device: "cuda:0" #推理设备 batch : 50 #批处理大小,更大的批处理大小可以提供更高的吞吐量,从而缩短推理所需的总时间。 max_det : 4 #最多检测的物体数 augment : False #启用测试时增强 (TTA) 进行预测,可能会提高检测的鲁棒性,但会降低推理速度。 verbose : False #是否在终端输出推理的详细信息。 ``` 对于路标检测正常调试只需要更改两个参数,分别是conf: 0.92 最小置信度阈值,这个表示看到这个物体相似度高于0.92才会框选。max_det : 2 最多检测的物体数,同一时间能同时检测多少对象。其他得参数要详细了解可以去看注释。 参数修改完之后重新编译,下次运行就会使用修改后的参数, ``` cd ~/yahboomcar_ros2_ws/yahboomcar_ws/ ``` ``` colcon build --packages-select auto_drive ``` 准备好路标 直行、右转、鸣笛、人行道  限速、停止、学校、停车场B  红绿灯、停车场A  ## 3.运行案例程序 自动驾驶源码路径:`~/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/auto_drive/yolo_detect.py` 启动相机节点 ``` ros2 launch ascamera hp60c.launch.py ``` 启动车道线居中 ``` ros2 run auto_drive yolo_detect ```  将路标放到画面中间会识别出正确的路标名称,max_det : 2同一时间只识别两个路标,自动驾驶过程中可能出现误识别情况,建议修改成max_det : 2。  max_det : 4 同一时间识别四个路标  保证道路上路标都能识别了,靠近一点识别率会更好,可以进行下一步调试。 ## 4.源码解析 ### 4.1、yolo_detect.py 程序源码路径: ``` ~/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/auto_drive/yolo_detect.py ``` **控制流程 (Control Flow)** 1. **图像回调** (image_callback): * 将ROS图像消息转换为OpenCV格式 * 将图像放入处理队列 2. **标志检测处理** (handle_sign): * 从队列中获取图像帧 * 使用YOLO模型进行目标检测 * 处理检测结果: * 过滤忽略的标志(如"turnright_ground", "sidewalk_ground") * 发布检测到的标志信息 * 在调试模式下显示FPS和推理时间 * 实时显示检测结果 主线程负责接收图像,工作线程负责处理图像和检测任务,通过队列进行线程间通信。 ``` def handle_sign(self): '''处理图像中的道路标识检测结果''' while True: try: frame = self.sign_detect.image_queue.get(timeout=0.01) except queue.Empty: continue infer_start = time.time() results=self.sign_detect.get_infer_result(frame,True) for res in results: if res.boxes is not None: annotated_frame = res.plot() boxes = res.boxes for i in range(len(boxes)): box_coords = boxes.xyxy[i].tolist()# 获取边界框坐标 (xyxy格式: xmin, ymin, xmax, ymax) class_name = res.names[int(boxes.cls[i].item())]# 获取物体名称 confidence = boxes.conf[i].item()# 获取置信度 # 检查是否为需要忽略的标志 if class_name in self.ignored_signs: # rospy.loginfo(f"Ignoring sign: {class_name}") continue # 跳过忽略的标志 # 发布检测结果 if self.sign_pub_counter % 5 == 0: self.sign_publisher.publish(DetectionObject( class_name=class_name, confidence=confidence, xmin=float(box_coords[0]), ymin=float(box_coords[1]), xmax=float(box_coords[2]), ymax=float(box_coords[3]) )) self.sign_pub_counter += 1 if self.DEBUG_MODE: infer_end = time.time() # 更新FPS self.frame_count += 1 curr_time = time.time() time_diff = curr_time - self.prev_time if time_diff >= 1.0: self.fps = self.frame_count / time_diff self.frame_count = 0 self.prev_time = curr_time # 在图像上显示FPS cv2.putText(annotated_frame,f"FPS: {self.fps:.2f}",(10, 25),cv2.FONT_HERSHEY_SIMPLEX,0.6,(0, 255, 0),1,) # 显示推理时间 infer_time = (infer_end - infer_start) * 1000 cv2.putText(annotated_frame, f"Infer: {infer_time:.1f} ms", (10, 45),cv2.FONT_HERSHEY_SIMPLEX, 0.6, (0, 255, 255), 1) cv2.imshow("Sign-Detect Panel", annotated_frame) cv2.waitKey(1) ```
admin
2025年12月6日 23:22
49
转发
收藏文档
上一篇
下一篇
手机扫码
复制链接
手机扫一扫转发分享
复制链接
Markdown文件
Word文件
PDF文档
PDF文档(打印)
分享
链接
类型
密码
更新密码
有效期
AI