gazebo仿真尝试

ROS 2接口与配置迁移指南 (从仿真到实车)

本文档旨在作为将 gazebo_robot_sim_py 仿真项目移植到真实硬件平台的操作手册。核心思想是:用真实的传感器驱动替换Gazebo插件,并调整配置文件以匹配真实机器人的物理特性。

第一部分:SLAM (Cartographer) 接口与配置

slam_launch.py 启动的SLAM流程中,您的实车需要替换Gazebo提供的传感器数据,并可能需要调整Cartographer的配置。

1. 必需的输入话题 (Your Vehicle MUST Provide These)

接口 (话题) 消息类型 发布者 (仿真中) 订阅者 (仿真中) 实车操作指南
/scan sensor_msgs/LaserScan Gazebo激光雷达插件 cartographer_node 【核心任务】 您的激光雷达驱动程序必须发布此话题。确保消息的 frame_id 与您机器人TF树中的激光雷达坐标系名称一致(例如 laser_link)。
/odom nav_msgs/Odometry Gazebo差分驱动插件 cartographer_node 【核心任务】 您的底层运动控制器或轮式里程计驱动程序必须发布此话题。这提供了机器人的速度和位姿初步估计。frame_id 应为 odomchild_frame_id 应为 base_link
/tf tf2_msgs/TFMessage Gazebo差分驱动插件,robot_state_publisher, static_transform_publisher cartographer_node 【核心任务】 您的机器人TF树必须完整且正确。具体包括: 1. odom -> base_link:通常由里程计发布者(如差分驱动插件)提供。 2. base_link -> laser_link:这是激光雷达相对于机器人中心的物理安装位置。在仿真中由 s

2. 关键的输出话题 (Cartographer Provides These for You)

接口 (话题) 消息类型 发布者 (仿真中) 订阅者 (仿真中) 实车调试要点
/map nav_msgs/OccupancyGrid cartographer_occupancy_grid_node rviz2 这是最终生成的2D栅格地图。您可以在RViz中订阅此话题来查看建图效果。
/tf tf2_msgs/TFMessage cartographer_node rviz2 Cartographer会发布**map -> odom** 的TF变换。这是SLAM的核心输出,它修正了里程计的累积误差,将机器人定位在全局地图中。

3. 需要重点关注的配置文件

  • urdf/robot.urdf:

    • 物理尺寸: 修改 base_link, left_wheel, right_wheel 等连杆的 <visual><collision> 标签中的尺寸,以匹配您的真实机器人。
    • 惯性参数: 粗略估计或测量各部件的 <inertial> 参数(质量和惯性张量)。虽然对2D SLAM影响不大,但对物理模型的准确性有好处。
    • 移除Gazebo插件: 【关键】 删除或注释掉所有 <gazebo> 标签。这包括差分驱动插件和激光雷达传感器插件。这些功能将由您的真实硬件驱动程序替代。
  • config/cartographer_config.lua:

    • tracking_frame: 确保这是您机器人URDF中的基座坐标系名称,通常是 base_link
    • odom_frame: 确保这是您的里程计发布的坐标系名称,通常是 odom
    • num_laser_scans: 如果您有多个激光雷达,需要修改此值并添加相应的订阅话题配置。
    • 性能调优: min_range, max_range, voxel_filter_size, submaps.num_range_data 等参数可能需要根据您的激光雷达型号和环境进行调优,以获得更好的建图效果。
  • launch/slam_launch.py:

    • static_tf_base_to_laser: 【关键】 修改此 Nodearguments,以反映激光雷达在您真实车辆上的精确(x, y, z)安装位置。
    • 移除Gazebo: 您可以删除 gazebospawn_entity 节点,因为不再需要仿真环境。
    • teleop_twist_keyboard: 您可以使用任何方式发布 /cmd_vel 指令来控制机器人,键盘遥控只是其中一种。

第二部分:Navigation (Nav2) 接口与配置

navigation_launch.py 启动的导航流程中,除了SLAM部分已提到的接口外,还需要关注Nav2自身的配置。

1. 必需的输入接口 (Your System MUST Provide These)

除了SLAM部分的 /scan, /odom, /tf 之外,Nav2还需要:

接口 (话题/服务/动作) 类型 发布者/客户端 (仿真中) 订阅者/服务器 (仿真中) 实车操作指南
/initialpose PoseWithCovarianceStamped initial_pose_publisher 或 RViz amcl 【关键】 在开始导航前,必须为AMCL提供一个初始位姿估计。这可以通过RViz手动设置,或运行 initial_pose_publisher节点自动设置。您需要确保发布的位姿在地图上的位置是准确的。
/goal_pose PoseStamped RViz或您自己的应用 nav2_bt_navigator 【关键】 这是导航的目标点。您可以通过RViz的 “Nav2 Goal” 工具发布,或编写自己的节点来发布。
/cmd_vel Twist (Nav2提供) nav2_controller 您的机器人底层驱动 【核心任务】 您需要编写一个底层驱动节点,该节点订阅 /cmd_vel 话题,并将收到的速度指令(linear.xangular.z)转换为对您机器人电机/舵机的实际控制信号。

2. 关键的输出接口 (Nav2 Provides These for You)

接口 (话题/服务/动作) 类型 发布者/服务器 实车调试要点
/plan Path nav2_planner 显示全局规划路径。
/local_plan Path nav2_controller (DWB) 显示本地规划路径。
/amcl_pose PoseWithCovarianceStamped amcl AMCL发布的机器人当前位姿和不确定性。
/global_costmap/costmap OccupancyGrid nav2_costmap_2d 全局代价地图。
/local_costmap/costmap OccupancyGrid nav2_costmap_2d 本地代价地图。

3. 需要重点关注的配置文件

  • urdf/robot.urdf:

    • 同SLAM部分,但这里的重点是确保物理尺寸和碰撞模型准确,因为Nav2的代价地图和路径规划器严重依赖这些信息来避免碰撞。
  • config/nav2_params.yaml:

    • amcl:
      • base_frame_id, odom_frame_id, global_frame_id: 确保与您的TF树一致。
      • scan_topic: 确保设置为 /scan
    • controller_server (DWB):
      • max_vel_x, max_vel_theta, acc_lim_x, acc_lim_theta: 【关键】 这些参数必须根据您真实机器人的最大速度和加速度能力进行修改。这是决定导航性能和安全性的最重要参数之一。
      • min_vel_x: 如果您的机器人不能以极低速度稳定行驶,可能需要设置一个非零的最小速度。
    • local_costmap & global_costmap:
      • robot_radiusfootprint: 【关键】 如果您的机器人是圆形的,请设置准确的 robot_radius。如果不是,请使用 footprint 参数定义其精确的多边形轮廓。这直接影响碰撞检测。
      • inflation_radius: 膨胀半径,定义了机器人离障碍物多远才算安全。需要根据机器人尺寸和期望的行驶行为进行调整。
      • scan (in observation_sources): 确保话题名称、传感器量程等与您的真实激光雷达匹配。
    • planner_server (NavFn):
      • tolerance: 到达目标的容忍距离,可以根据精度要求调整。
    • map_server:
      • yaml_filename: 在 navigation_launch.py中,这个参数会被动态设置为您选择的地图文件。
    • bt_navigator: 通常不需要修改,除非您想自定义行为树。
  • launch/navigation_launch.py:

    • 移除Gazebo: 同SLAM部分,移除 gazebospawn_entity 节点。
    • map argument: 确保您在启动时传入的地图文件 (my_map.yaml) 是您通过SLAM构建并保存的真实环境地图。
    • initial_pose_publisher: 修改此节点的参数,以匹配您希望机器人在地图上的默认启动位置。

迁移工作流总结

  1. 硬件驱动: 编写或配置您的激光雷达驱动和电机控制器,使其分别发布 /scan 话题和订阅 /cmd_vel 话题,并发布 /odomodom->base_link 的TF。

  2. URDF修改: 更新 robot.urdf 以反映真实机器人的尺寸、碰撞模型和关节。移除所有Gazebo插件

  3. TF树验证:

    • 测量并更新 launch/slam_launch.pylaunch/navigation_launch.py 中的 static_tf_base_to_laser
    • 运行 ros2 run tf2_tools tf2_echo map base_linkros2 run tf2_tools tf2_echo base_link laser_link 来验证TF树是否正确连接。
  4. SLAM测试:

    • 运行修改后的 slam_launch.py
    • 遥控机器人在环境中移动,观察RViz中的建图效果。
    • 根据效果调整 config/cartographer_config.lua
    • 建图完成后,使用 ros2 run nav2_map_server map_saver_cli -f <your_map_name> 保存地图。
  5. 导航配置:

    • 将保存的地图文件(.pgm.yaml)放入 maps 文件夹。
    • 仔细修改 config/nav2_params.yaml 中的机器人物理参数(速度、加速度、尺寸)。
  6. 导航测试:

    • 运行修改后的 navigation_launch.py,并确保 map 参数指向您新保存的地图。
    • 在RViz中设置初始位姿,观察AMCL粒子是否收敛。
    • 在RViz中设置导航目标,观察机器人是否能够安全、平稳地到达。
    • 根据导航行为反复调试 nav2_params.yaml中的参数。
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
<?xml version="1.0"?>
<robot name="mobile_robot">
<!-- ======================= LINKS ======================= -->

<link name="base_link">
<visual>
<geometry>
<box size="0.4 0.3 0.1"/>
</geometry>
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
</visual>
<collision>
<geometry>
<box size="0.4 0.3 0.1"/>
</geometry>
</collision>
<inertial>
<mass value="2.0"/>
<inertia ixx="0.015" ixy="0" ixz="0" iyy="0.0267" iyz="0" izz="0.0367"/>
</inertial>
</link>

<!-- Left Wheel (Resized) -->
<link name="left_wheel">
<visual>
<geometry>
<cylinder radius="0.05" length="0.05"/> <!-- MODIFIED: radius 0.1 -> 0.05 -->
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.05"/> <!-- MODIFIED: radius 0.1 -> 0.05 -->
</geometry>
</collision>
<inertial>
<!-- MODIFIED: Reduced mass and inertia for smaller wheel -->
<mass value="0.2"/>
<inertia ixx="0.00015" ixy="0" ixz="0" iyy="0.00015" iyz="0" izz="0.00025"/>
</inertial>
</link>

<joint name="left_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="left_wheel"/>
<!-- The z=0 origin is now correct for a radius of 0.05 -->
<origin xyz="-0.1 0.175 0" rpy="-1.5708 0 0"/>
<axis xyz="0 0 1"/>
</joint>

<!-- Right Wheel (Resized) -->
<link name="right_wheel">
<visual>
<geometry>
<cylinder radius="0.05" length="0.05"/> <!-- MODIFIED: radius 0.1 -> 0.05 -->
</geometry>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.05" length="0.05"/> <!-- MODIFIED: radius 0.1 -> 0.05 -->
</geometry>
</collision>
<inertial>
<!-- MODIFIED: Reduced mass and inertia for smaller wheel -->
<mass value="0.2"/>
<inertia ixx="0.00015" ixy="0" ixz="0" iyy="0.00015" iyz="0" izz="0.00025"/>
</inertial>
</link>

<joint name="right_wheel_joint" type="continuous">
<parent link="base_link"/>
<child link="right_wheel"/>
<!-- The z=0 origin is now correct for a radius of 0.05 -->
<origin xyz="-0.1 -0.175 0" rpy="-1.5708 0 0"/>
<axis xyz="0 0 1"/>
</joint>

<!-- Caster Wheel -->
<link name="caster_wheel">
<visual>
<geometry>
<sphere radius="0.05"/>
</geometry>
<material name="gray">
<color rgba="0.5 0.5 0.5 1"/>
</material>
</visual>
<collision>
<geometry>
<sphere radius="0.05"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.0001" ixy="0" ixz="0" iyy="0.0001" iyz="0" izz="0.0001"/>
</inertial>
</link>

<joint name="caster_wheel_joint" type="fixed">
<parent link="base_link"/>
<child link="caster_wheel"/>
<!-- MODIFIED: z origin -0.05 -> 0 to keep the robot level with new smaller wheels -->
<origin xyz="0.15 0 0" rpy="0 0 0"/>
</joint>

<!-- Laser Scanner Link -->
<link name="laser_link">
<visual>
<geometry>
<cylinder radius="0.04" length="0.04"/>
</geometry>
<material name="black">
<color rgba="0.2 0.2 0.2 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="0.04" length="0.04"/>
</geometry>
</collision>
<inertial>
<mass value="0.1"/>
<inertia ixx="0.00002" ixy="0" ixz="0" iyy="0.00002" iyz="0" izz="0.00002"/>
</inertial>
</link>

<joint name="laser_joint" type="fixed">
<parent link="base_link"/>
<child link="laser_link"/>
<origin xyz="0.2 0 0.08" rpy="0 0 0"/>
</joint>

<!-- ======================= GAZEBO ======================= -->

<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="left_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="right_wheel">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="caster_wheel">
<material>Gazebo/Gray</material>
<mu1>0.0</mu1>
<mu2>0.0</mu2>
</gazebo>
<gazebo reference="laser_link">
<material>Gazebo/Black</material>
</gazebo>

<gazebo>
<plugin name="diff_drive" filename="libgazebo_ros_diff_drive.so">
<update_rate>50</update_rate>
<left_joint>left_wheel_joint</left_joint>
<right_joint>right_wheel_joint</right_joint>
<wheel_separation>0.35</wheel_separation>
<!-- CRITICAL MODIFICATION: Diameter must match the new wheel size (radius 0.05 * 2) -->
<wheel_diameter>0.1</wheel_diameter>
<command_topic>cmd_vel</command_topic>
<odometry_topic>odom</odometry_topic>
<odometry_frame>odom</odometry_frame>
<robot_base_frame>base_link</robot_base_frame>
<publish_odom>true</publish_odom>
<publish_odom_tf>true</publish_odom_tf>
<publish_wheel_tf>true</publish_wheel_tf>
</plugin>
</gazebo>

<gazebo reference="laser_link">
<sensor type="ray" name="laser_sensor">
<pose>0 0 0 0 0 0</pose>
<visualize>true</visualize>
<update_rate>10</update_rate>
<ray>
<scan>
<horizontal>
<samples>360</samples>
<resolution>1</resolution>
<min_angle>-3.14159</min_angle>
<max_angle>3.14159</max_angle>
</horizontal>
</scan>
<range>
<min>0.10</min>
<max>10.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_laser" filename="libgazebo_ros_ray_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=scan</remapping>
</ros>
<output_type>sensor_msgs/LaserScan</output_type>
<frame_name>laser_link</frame_name>
</plugin>
</sensor>
</gazebo>
</robot>
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
<?xml version="1.0"?>
<sdf version="1.6">
<world name="my_world">
<physics type="ode">
<real_time_update_rate>100</real_time_update_rate>
<max_step_size>0.01</max_step_size>
</physics>
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<model name="wall_front">
<static>true</static>
<pose>5 0 1 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="wall_back">
<static>true</static>
<pose>-5 0 1 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="wall_left">
<static>true</static>
<pose>0 5 1 0 0 1.5708</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="wall_right">
<static>true</static>
<pose>0 -5 1 0 0 1.5708</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>0.2 10 2</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Grey</name>
</script>
</material>
</visual>
</link>
</model>
<model name="obstacle1">
<static>true</static>
<pose>2 2 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<script>
<name>Gazebo/Orange</name>
</script>
</material>
</visual>
</link>
</model>
</world>
</sdf>