一、概述
1.1 为什么要仿真
搭建Gazebo仿真环境对于智能车比赛(特别是涉及视觉巡线、强化学习等算法开发)来说,不是可选项,而是最优解。以下是需要搭建仿真环境的核心理由,以及它能解决的实际问题。
1.1.1 硬件不足
问题:你现在没有久久派、摄像头、电机等硬件,但需要写程序、验证算法。
Gazebo的作用:
- 提供虚拟的小车模型(带摄像头、激光雷达等传感器);
- 提供虚拟的赛道环境(可以自定义颜色、形状、材质);
- 程序写完后,直接在Gazebo里运行,效果等同于在真车上测试;
结果:硬件还没到,你的巡线算法已经跑通了。硬件一到,只需换底层驱动即可。
1.1.2 缩短调试周期
调试场景真车调试Gazebo仿真修改PID参数烧录→上电→跑一圈→观察→再烧录(5-10分钟/次)改代码→保存→重启仿真(10秒/次)小车撞墙可能损坏硬件(电机、舵机、车架)重置位置,继续调试跑完一整圈需要清场、充电、防止撞人无限制运行,无人值守测试极端情况可能翻车、失控完全安全结论:仿真环境让的调试效率提升30-50倍。
1.1.3 提供可复现的测试环境
问题:真车测试时,光线变化、地面摩擦力、电池电量都会影响结果,今天跑通的代码明天可能就失效。
Gazebo的优势:
- 每次启动都是完全相同的环境(相同的光照、相同的摩擦力、相同的传感器噪声);
- 可以精确控制变量:比如只改变线条颜色,其他不变;
- 算法性能变化只由代码改动引起,排除了环境干扰;
这对于调参、对比算法优劣至关重要。
1.1.4、支持强化学习训练
强化学习需要数百万次试错,这在真车上完全不可能:
训练需求真车Gazebo仿真试错次数几百次就报废无限次训练速度1倍速可以加速到10-100倍并行训练需要多台真车开多个Gazebo实例复位成本手动搬回起点代码一键复位实例:训练一个简单的巡线RL模型,真车可能需要3个月+损坏5台车,仿真只需要1周+电费。
1.1.5、提前发现算法缺陷
仿真中可以轻松制造"事故场景":
- 突然的强光照射(模拟阳光直射摄像头);
- 赛道上有污渍(模拟线条部分缺失);
- 传感器故障(模拟某个像素坏点);
这些在真车上很难刻意制造,但在仿真中可以随时开启。提前让你的算法适应这些情况,比赛时就不会翻车。
1.2 环境搭建步骤
走马观碑组Gazebo仿真环境搭建主要包含以下几个步骤:
① 环境准备(ubuntu + ROS2):这个可以参考《ROS2概述和基于RK3588的环境搭建》;
② 小车建模(URDF):有关URFD介绍可以参考《ROS2之URDF建模》;
③ 赛道建模(World);
④ 视觉巡线算法开发。
1.2.1 工程目录简介
我们可以先创建工程目录,创建目录car_ws;- zhengyang@ubuntu:~$ cd /opt/2k0300/loongson_2k300_lib
- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib$ mkdir -p car_ws/src
- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib$ cd car_ws/src
复制代码 完整的目录结构大致如下,这个我们后续内容会依次创建:- car_ws/
- ├── src/
- │ ├── car_description/ # 功能包1:机器人URDF模型
- │ ├── car_gazebo/ # 功能包2:Gazebo仿真
- │ └── car_vision/ # 功能包3:视觉算法
复制代码 在ROS的开发规范中,src/ 下的每个子目录叫功能包(Package),而不是独立项目。它们共同组成一个完整的机器人项目。
功能包职责修改频率car_description小车的物理模型(尺寸、颜色、传感器位置)低(硬件确定后很少改)car_gazebo仿真环境、赛道、启动脚本中(换赛道时需要改)car_vision图像处理、巡线算法高(天天调参)1.2.2 功能包关系
功能包之间的协作关系如下:- 启动顺序:
- 1. car_gazebo 启动仿真世界,生成小车模型
- └── 调用 car_description 中的 car.urdf 描述小车长什么样
- 2. car_vision 订阅摄像头图像
- └── 处理图像 → 发布速度指令
- 3. car_gazebo 中的 Gazebo 接收速度指令
- └── 驱动仿真小车运动
复制代码 二、小车建模
创建car_description的Python版本的功能包;- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ ros2 pkg create --build-type ament_python car_description
复制代码 运行成功后,终端会显示创建的文件和目录信息。此时, car_description 功能包目录结构将如下所示:- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ tree ./car_description/
- ./car_description/
- ├── car_description # 核心Python模块目录,用于存放Python代码
- │ └── __init__.py
- ├── package.xml # 功能包的描述文件(含依赖信息)
- ├── resource # 资源文件夹
- │ └── car_description
- ├── setup.cfg # setuptools 的配置文件
- ├── setup.py # Python 包的安装脚本
- └── test # 测试文件夹
复制代码 2.1 子目录
功能包创建好了,但按照规划我们需要在 car_description 中存放小车的URDF模型文件。这些不是.py文件,放在自动生成的 car_description 子目录下并不合适。
我们可以手动创建多个目录来更好地组织文件:
- urdf: 专门存放 .urdf 或 .xacro 模型文件;
- launch:保存相关启动文件;
- rviz:保存rviz的配置文件;
- meshes:放置URDF中引用的模型渲染文件;
- config: 存放Gazebo控制器的配置文件。
在终端中执行:- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src$ cd car_description/
- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description$ mkdir urdf config launch rviz meshes
复制代码 我们需要修改setup.py文件,添加配置文件:- import os
- from glob import glob
- ...
- data_files=[
- ('share/ament_index/resource_index/packages',
- ['resource/' + package_name]),
- ('share/' + package_name, ['package.xml']),
- (os.path.join('share', package_name, 'launch'), glob(os.path.join('launch', '*.launch.py'))),
- (os.path.join('share', package_name, 'urdf'), glob(os.path.join('urdf', '*.*'))),
- (os.path.join('share', package_name, 'urdf/sensors'), glob(os.path.join('urdf/sensors', '*.*'))),
- (os.path.join('share', package_name, 'meshes'), glob(os.path.join('meshes', '*.*'))),
- (os.path.join('share', package_name, 'rviz'), glob(os.path.join('rviz', '*.rviz'))),
- (os.path.join('share', package_name, 'config'), glob(os.path.join('config', '*.*'))),
- ],
- ...
复制代码 2.2 模型文件
接下来就是编写一个完整的 car.xacro 文件,这个模型包含车身、三个轮子、摄像头传感器,并且配置了Gazebo仿真所需的插件;
- 有关URDF语法可以参考《ROS2之URDF建模》;
- 有关XACRO语法可以参考《ROS2之Gazebo物理仿真平台》。
首先进入 urdf 目录并创建文件:- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description$ cd urdf/
- zhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws/src/car_description/urdf$ vim car.xacro
复制代码 内容如下:
点击查看详情这里我们通过通过 nose 和 main_body 的组合来模拟车模前窄后宽的形状,这更符合F车模的真实外观;
- 长:18cm、宽20cm、高6.5cm;
- 车轮:直径6.4cm、宽度2.7cm、轮距15.5cm。
2.2.1 车身几何结构
使用了两个 来拼接车身;
- 后部 (main_body):尺寸0.11m x 0.16m,这是电机和后轮所在的位置,比较宽;
- 前部 (nose):尺寸0.07m x 0.06m,这是向前延伸的部分,模拟真实的窄支架;
总长:0.11 + 0.07 = 0.18m。
2.2.2 轮距与轮子
wheel_track 设为0.155m。
轮子坐标通过 ${-main_body_len/2 + 0.01} 计算,确保轮子安装在后底盘的边缘,而不是车身中心。
2.2.3 万向轮位置
万向轮安装在 caster_offset_x (0.08m) 处,这大约在前部支架的中间位置,既保证了支撑稳定性,又不会因为太靠前而在转弯时产生过大的阻力矩。
2.2.4 摄像头高度
为了适应“走马观碑”组别,我将摄像头高度设定为离地约12cm (camera_height),并增加了一个俯仰角 camera_pitch,这更符合实际比赛中俯视赛道的情况。
当然如果熟悉SolidWorks或Fusion 360可以按照图片画一个精确的3D模型,将其导出为 .stl 或 .dae 文件。在URDF中,把 标签换成:- [/code]这样在rviz和Gazebo中看到的就完全是一模一样的车了。
- [size=3]2.3 launch文件[/size]
- 在launch文件夹下创建display.launch.py文件;
- [code]from launch import LaunchDescription
- from launch.actions import DeclareLaunchArgument
- from launch_ros.parameter_descriptions import ParameterValue
- from launch_ros.actions import Node
- from launch.substitutions import Command, LaunchConfiguration
- from ament_index_python.packages import get_package_share_directory
- import os
- def generate_launch_description():
- # xacro 文件路径(注意扩展名是 .xacro)
- xacro_path = os.path.join(
- get_package_share_directory('car_description'),
- 'urdf',
- 'car.xacro' # 关键:改为 .xacro
- )
-
- # 声明 model 参数
- model_arg = DeclareLaunchArgument(
- name='model',
- default_value=xacro_path,
- description='Absolute path to robot xacro file'
- )
-
- # 使用 xacro 命令解析 URDF
- robot_description = ParameterValue(
- Command(['xacro ', LaunchConfiguration('model')]),
- value_type=str
- )
-
- return LaunchDescription([
- model_arg, # 必须包含这个声明
-
- # 机器人状态发布器
- Node(
- package='robot_state_publisher',
- executable='robot_state_publisher',
- output='screen',
- parameters=[{'robot_description': robot_description}]
- ),
-
- # 关节状态发布器 GUI(可手动拖动关节)
- Node(
- package='joint_state_publisher_gui',
- executable='joint_state_publisher_gui',
- name='joint_state_publisher_gui'
- ),
-
- # RViz2 可视化
- Node(
- package='rviz2',
- executable='rviz2',
- name='rviz2',
- arguments=['-d', os.path.join(get_package_share_directory('car_description'), 'rviz', 'car_display.rviz')],
- output='screen'
- )
- ])
复制代码 这个Launch文件主要做三件事:
- 加载机器人URDF模型(支持xacro格式);
- 发布机器人的状态变换(TF);
- 在rviz2中可视化机器人。
2.3.1 节点
脚本运行会创建以下几个节点:
- joint_state_publisher_gui:发布每个joint(除fixed类型)的状态,可以通过UI界面对joint进行控制;
- robot_state_publisher:将机器人各个links、joints之间的关系,通过TF的形式,整理成三维姿态信息发布。
- rviz2:在rviz2中可视化机器人;
joint_state_publisher这是一个官方ROS2包,主要功能:
- 输入:
- 读取URDF中的关节定义;
- 接收用户或程序指定的关节角度;
- 输出:
- 发布 /joint_states 话题,消息类型为 sensor_msgs/msg/JointState;
- 包含所有关节的名称、位置、速度、力等信息。
2.3.2 数据流与节点关系
数据流与节点关系:- 用户通过滑动条/GUI或程序 → joint_state_publisher_gui
- ↓ 发布/joint_states话题
- robot_state_publisher
- ↓ 计算并发布TF变换
- rviz2 和其他节点
- ↓ 接收TF并可视化
复制代码 2.4 car_display.rviz
创建rviz配置文件,避免手动设置rviz,在rviz目录下新建car_display.rviz文件;- Panels:
- - Class: rviz_common/Displays
- Name: Displays
- - Class: rviz_common/Views
- Name: Views
- Visualization Manager:
- Class: ""
- Displays:
- - Class: rviz_default_plugins/Grid
- Name: Grid
- Value: true
- - Alpha: 0.8
- Class: rviz_default_plugins/RobotModel
- Description Source: Topic
- Description Topic:
- Value: /robot_description
- Enabled: true
- Name: RobotModel
- Value: true
- - Class: rviz_default_plugins/TF
- Name: TF
- Value: true
- Global Options:
- Fixed Frame: base_link
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz_default_plugins/MoveCamera
- Value: true
- Views:
- Current:
- Class: rviz_default_plugins/Orbit
- Distance: 1.7
- Name: Current View
- Pitch: 0.33
- Value: Orbit (rviz)
- Yaw: 5.5
- Window Geometry:
- Height: 800
- Width: 1200
复制代码 2.5 编译运行
2.4.1 编译
在 car_ws 目录下编译并检查:
[code]zhengyang@ubuntu:~$ cd /opt/2k0300/loongson_2k300_lib/car_wszhengyang@ubuntu:/opt/2k0300/loongson_2k300_lib/car_ws$ colcon build --paths src/car_description.....Finished |