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、数据采集
1、数据采集
# 数据集采集 >i **信息提示** > > * 机器人镜像已经包含了预设的训练路标识别模型和车道识别模型所需的数据集,本节教程提供给需要自行训练yolov11模型和想采集自己数据集的用户,如果需要直接体验完整功能,可略过本节课程!!! ## 1\. 课程内容 1. 掌握训练YOLOv11目标检测模型所需的数据集的采集方式 ,训练YOLOv11目标模型需要先准备包含待检测目标的数据集 ## 2\. 路标识别模型数据采集 ### 2.1 原理讲解 * 通过摄像头录制不同光照、背景下包换待检测目标的视频,然后通过截取固定间隔视频帧的方式获取原始图片数据集 ### 2.2 数据采集 * 启动录制数据集节点 ```驱动相机 ros2 launch ascamera hp60c.launch.py ``` ```录制 ros2 run auto_drive record_video output_path:=~ ``` 可选启动参数 * **output_path:**保存视频文件的路径 * **fps:**录制视频的帧率 * 运行程序后会启动一个视频窗口,可以通过移动底盘从不同角度、不同光照下录制包含待检测目标的视频素材,这样可以丰富数据集的多样性。 * 将要识别的路标放到视角内,开始录制视频  * 按ctrl+c键可以结束录制,终端会打印保存文件的路径  * 如果未指定视频输出路径,视频文件会默认保存在系统用户home目录下  * 分割视频帧为图片集,将源码汇总的《模型训练》文件夹下的split_video.py放到根目录下,运行下面指令 cd ~ * 修改output_dir、video_file为自己的图片输出路径和视频路径 python3 split_video.py --output_dir ~/output_frame --video_file ~/camera_record ing_20251117_140246.mp4 参数说明 * **video_file:** 需要分割的视频的路径 * **output_dir:**分割完图片保存的路径 * **start_number:**图片的起始编号 * **frame_interval:**视频帧间隔,指定每隔多少帧截取一张图片 * * * * 分割视频帧完成后终端会打印提示信息  * 分割完的图像会保存在output\_dir指定的文件夹中  ## 3\. 车道识别模型数据集采集 车道识别模型数据采集流程和路标识别模型数据采集流程相同 ### 3.1 数据采集 * 启动录制数据集节点 #驱动相机 ros2 launch ascamera hp60c.launch.py #录制 ros2 run auto_drive record_video output_path:=~ 可选启动参数 * **output_path:**保存视频文件的路径 * **fps:**录制视频的帧率 * * * * 鼠标放在Record-Video-panel窗口上,按s键,开始录制视频  * 视频保存和分割的方法和前边完全一致,这里不再进行赘述。 ## 4\. 源码讲解 ### 4.1从视频话题录制视频 * 源码位于auto_drive功能包中的record_video.py,源码路径: #orin nano 、rdkx5 ~/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/auto_drive/record_video.py * 图像回调函数(image\_callback 方法)每次收到图像消息时触发,负责: 格式转换:通过 self.bridge.imgmsg\_to\_cv2 将 ROS 图像消息(msg)转换为 OpenCV 格式(cv\_image,bgr8 编码,对应 RGB 色彩空间)。 显示图像:用 cv2.imshow 弹出名为 Record-Video-Panel 的窗口,实时显示图像。 按键控制:通过 cv2.waitKey(1) 检测按键(1ms 延迟,保证窗口刷新): 按 s 键:切换录制状态(未录制则启动,正在录制则停止)。 录制逻辑:若 self.is\_recording 为 True,则通过 self.out.write(cv\_image) 将当前帧写入视频,并计数(每录制 100 帧打印一次日志)。 异常处理:捕获转换或录制中的错误,用红色日志提示。 * ``` def image_callback(self, msg): try: cv_image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8') cv2.imshow("Record-Video-Panel", cv_image) key = cv2.waitKey(1) & 0xFF if key == ord('s'): if not self.is_recording: # 开始录制Start recording self.start_recording(cv_image) else: # 停止录制Stop recording self.stop_recording() # 如果正在录制,则写入帧If recording is in progress, write the frame. if self.is_recording and self.out is not None: self.out.write(cv_image) self.frame_count += 1 if self.frame_count % 100 == 0: self.get_logger().info(f"Recorded {self.frame_count} frames") except Exception as e: self.get_logger().info(Fore.RED+f"Error processing image: {str(e)}"+Fore.RESET) ``` * 录制控制方法 start\_recording 方法(开始录制) 初始化 cv2.VideoWriter: 获取第一帧图像的宽高(first\_frame.shape\[:2\],OpenCV 格式为 (高, 宽))。 用 cv2.VideoWriter\_fourcc 解析编码格式(fourcc\_code,如 mp4v 对应 \*'mp4v')。 拼接视频保存路径,创建 VideoWriter 实例(参数:路径、编码、帧率、宽高)。 校验初始化:若 VideoWriter 未成功打开(如路径错误或编码不支持),打印红色错误日志。 更新状态:self.is\_recording = True,并打印绿色日志提示录制开始。 stop\_recording 方法(停止录制) 更新状态:self.is\_recording = False。 释放资源:若 self.out 存在(即正在录制),调用 self.out.release() 关闭视频文件,确保数据写入完成。 重置计数:self.frame\_count = 0,self.out = None(下次录制重新初始化)。 打印日志:视频保存路径(绿色)和重新录制提示(黄色)。 ``` def start_recording(self, first_frame): """开始录制视频Start recording video""" if self.out is None: self.frame_height, self.frame_width = first_frame.shape[:2] fourcc = cv2.VideoWriter_fourcc(*self.fourcc_code) video_path = os.path.join(self.output_path, self.video_name) self.out = cv2.VideoWriter( video_path, fourcc, self.fps, (self.frame_width, self.frame_height) ) if not self.out.isOpened(): self.get_logger().error(Fore.RED+"Unable to open video editor. Please check the encoding format and output path."+Fore.RESET) return self.get_logger().info(Fore.GREEN+f"Start recording video - resolution: {self.frame_width}x{self.frame_height}"+Fore.RESET) self.is_recording = True self.get_logger().info(Fore.YELLOW+"Recording started... Press 's' to stop."+Fore.RESET) def stop_recording(self): """停止录制视频Stop recording video""" self.is_recording = False if self.out is not None: self.out.release() self.get_logger().info(Fore.GREEN+f"Video save path: {os.path.join(self.output_path, self.video_name)}"+Fore.RESET) self.out = None self.frame_count = 0 self.get_logger().info(Fore.YELLOW+"Recording stopped. Press 's' to start a new recording."+Fore.RESET) ``` ### 4.2 启动launch程序 * 用于启动相机驱动和4.1从相机图像话题录制视频的节点 * 源码位于auto_drive功能包中的record_video.launch.py,源码路径: #orin nano 、rdkx5 ~/yahboomcar_ros2_ws/yahboomcar_ws/src/auto_drive/launch/record_video.launch.py * 从环境变量 CAMERA_TYPE 读取相机类型: 若为 nuwa:启动 hp60c.launch.py 相机驱动,订阅图像话题 /ascamera_hp60c/camera_publisher/rgb0/image。 * 节点启动逻辑 先启动适配的相机驱动(bringup\_camera\_launch),确保图像流正常发布。 再启动视频录制节点(record\_video\_node),传入参数:保存路径、帧率、对应相机的图像话题。 录制节点(对应之前的 ImageToVideoNode)会订阅指定图像话题,执行录制功能。 ``` import os from ament_index_python.packages import get_package_share_directory from launch import LaunchDescription from launch_ros.actions import Node from launch.launch_description_sources import PythonLaunchDescriptionSource from launch.actions import IncludeLaunchDescription,TimerAction from launch.actions import DeclareLaunchArgument from launch.substitutions import LaunchConfiguration def generate_launch_description(): CAMERA_TYPE = os.environ['CAMERA_TYPE']#获取相机类型Get camera type m3_bringup_dir=os.path.join(get_package_share_directory('auto_drive')) if CAMERA_TYPE == 'nuwa': bringup_camera_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([ os.path.join(get_package_share_directory('ascamera'), 'launch'), '/hp60c.launch.py' ]) ) elif CAMERA_TYPE == 'usb': bringup_camera_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([ os.path.join(get_package_share_directory('usb_cam'), 'launch'), '/camera.launch.py' ]) ) #启动参数Startup parameters declared_arguments = [] declared_arguments.append( DeclareLaunchArgument( "output_path", default_value="~", description="Video save path/视频保存路径 ", ) ) declared_arguments.append( DeclareLaunchArgument( "fps", default_value=30, description="Video frame rate/视频帧率 ", ) ) output_path=LaunchConfiguration('output_path') fps = LaunchConfiguration('fps') record_video_ndoe=Node( package='auto_drive', executable='record_video', name='record_video', output='screen', parameters=[ {'output_path': output_path}, {'fps': fps}, {'image_topic': rgb_topic}, ], ) return LaunchDescription([ *declared_arguments, #声明启动参数Declare startup parameters bringup_camera_launch, #启动相机驱动 /Start the camera driver record_video_ndoe, #启动录制视频节点/Start recording video node ]) ``` ### 4.3 分割视频为图片集程序 * 源码路径: ~/Rosmaster/Sample/split_video.py * 核心流程(主函数) 初始化配置: 读取命令行参数,获取视频路径、输出文件夹等配置。 自动创建输出文件夹(若不存在)。 视频处理: 用 cv2.VideoCapture 打开视频文件,获取总帧数、帧率等信息。 循环读取视频帧,每间隔 frame\_interval 帧(如每 30 帧)保存 1 张图片: 图片命名以 start\_number 为起始,逐次递增(如 0.jpg、1.jpg)。 实时打印进度(当前帧 / 总帧数 + 保存的图片名)。 ``` import cv2 import os import argparse def get_args(): parser = argparse.ArgumentParser() parser.add_argument('--output_dir', default='engine', help='Output folder', type=str) parser.add_argument('--frame_interval',default=30 ,help='Capture an image at specified intervals from the video frames.', type=int) parser.add_argument('--video_file', default='', help='Original video path', type=str) parser.add_argument('--start_number', default=0, help='Image starting number', type=int) return parser.parse_args() if __name__ == "__main__": args = get_args() # Path to the input video file video_file =args.video_file # Path to the output folder to save the frames output_folder =args.output_dir # Check if the output folder exists, if not, create it if not os.path.exists(output_folder): os.makedirs(output_folder) # Open the video file using OpenCV cap = cv2.VideoCapture(video_file) # Get the total number of frames in the video total_frames = int(cap.get(cv2.CAP_PROP_FRAME_COUNT)) # Get the frames per second (fps) of the video fps = cap.get(cv2.CAP_PROP_FPS) # Frame counter to keep track of the current frame number frame_number = 0 # Define the interval for extracting frames (every 15th frame) frame_interval = args.frame_interval # Initialize a new counter for saved frames (starting from 1) start_number = args.start_number while True: ret, frame = cap.read() # If the frame is not successfully read, exit the loop if not ret: break # Save every 15th frame if frame_number % frame_interval == 0: # Format the frame number starting from 1 (e.g., 1.png, 2.png) image_name = f'{start_number}.jpg' image_path = os.path.join(output_folder, image_name) # Save the current frame as a PNG image cv2.imwrite(image_path, frame) print(f'Saving frame {frame_number}/{total_frames} as {image_name}') # Increment the saved frame counter start_number += 1 # Increment the frame counter for the video frame_number += 1 # Release the video capture object cap.release() # Print message when processing is complete print(f"Video processing complete! Every {frame_interval} frame saved as an image!") ```
admin
2025年12月28日 18:14
29
转发
收藏文档
上一篇
下一篇
手机扫码
复制链接
手机扫一扫转发分享
复制链接
Markdown文件
Word文件
PDF文档
PDF文档(打印)
分享
链接
类型
密码
更新密码
有效期
AI