本文档详细记录了将ROS2项目从Gazebo Classic迁移到Gazebo Harmonic (新版Gazebo)的完整过程,包括所有关键修改、对比分析以及在ROS2 Jazzy环境下使用仿真时需要注意的问题。
ROS2 Jazzy (Ubuntu 24.04) 不再支持Gazebo Classic,已经完全切换到新一代Gazebo仿真器(代号:Harmonic)。
| 特性 | Gazebo Classic | Gazebo Harmonic |
|---|---|---|
| 包名前缀 | gazebo_ros |
ros_gz / gz_ros2 |
| 仿真引擎 | 旧架构 | 全新重写 |
| ROS2支持 | Humble及以前 | Jazzy及以后 |
| 插件系统 | libgazebo_*.so |
原生Gazebo+桥接 |
| 性能 | 较慢 | 更快、更稳定 |
src/robot_description_pkg/launch/robot_display.launch.py
旧版 (Gazebo Classic):
from launch.launch_description_sources import PythonLaunchDescriptionSource
from ament_index_python.packages import get_package_share_directory
launch_gazebo = launch.actions.IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('gazebo_ros'),
'/launch',
'/gazebo.launch.py'
]),
launch_arguments=[('verbose', 'true')]
)
新版 (Gazebo Harmonic):
launch_gazebo = launch.actions.IncludeLaunchDescription(
PythonLaunchDescriptionSource([
get_package_share_directory('ros_gz_sim'),
'/launch',
'/gz_sim.launch.py'
]),
launch_arguments=[('gz_args', '-r empty.sdf')]
)
关键差异:
gazebo_ros → ros_gz_simgazebo.launch.py → gz_sim.launch.pyverbose → gz_args with SDF file旧版:
spawn_entity_node = launch_ros.actions.Node(
package='gazebo_ros',
executable='spawn_entity.py',
arguments=[
'-topic', '/robot_description',
'-entity', robot_name_in_model,
]
)
新版:
spawn_entity_node = launch_ros.actions.Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-topic', '/robot_description',
'-name', robot_name_in_model
],
output='screen'
)
关键差异:
gazebo_ros → ros_gz_simspawn_entity.py → create-entity → -nameoutput='screen' 用于调试新版Gazebo需要显式配置ROS-Gazebo桥接来传递传感器数据:
# IMU数据桥接
bridge_imu = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/imu@sensor_msgs/msg/Imu[gz.msgs.IMU'
],
output='screen'
)
# 相机数据桥接
bridge_camera = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/camera@sensor_msgs/msg/Image[gz.msgs.Image',
'/camera/depth@sensor_msgs/msg/Image[gz.msgs.Image',
'/camera/camera_info@sensor_msgs/msg/CameraInfo[gz.msgs.CameraInfo'
],
output='screen'
)
桥接格式说明:
/topic_name@ros_msg_type[gz_msg_type
src/robot_description_pkg/urdf/balance_car.ros2_control.xacro
旧版:
<ros2_control name="MyRobotGazeboSystem" type="system">
<hardware>
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
</hardware>
<!-- joints configuration -->
</ros2_control>
新版:
<ros2_control name="MyRobotGazeboSystem" type="system">
<hardware>
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
</hardware>
<!-- joints configuration -->
</ros2_control>
关键差异:
gazebo_ros2_control/GazeboSystem → gz_ros2_control/GazeboSimSystem旧版:
<gazebo>
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
<parameters>$(find robot_description_pkg)/config/balance_car_ros2_controller.yaml</parameters>
</plugin>
</gazebo>
新版:
<gazebo>
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters>$(find robot_description_pkg)/config/balance_car_ros2_controller.yaml</parameters>
</plugin>
</gazebo>
关键差异:
filename:.so共享库 → 系统名称name:简单名称 → 完整命名空间src/robot_description_pkg/plugins/gazebo_sensor_imu.xacro
旧版 (使用ROS插件):
<gazebo reference="imu_link">
<sensor name="imu_sensor" type="imu">
<plugin name="imu_plugin" filename="libgazebo_ros_imu_sensor.so">
<ros>
<namespace>/</namespace>
<remapping>~/out:=imu</remapping>
</ros>
<initial_orientation_as_reference>false</initial_orientation_as_reference>
</plugin>
<update_rate>100</update_rate>
<always_on>true</always_on>
<imu>
<!-- noise configuration -->
</imu>
</sensor>
</gazebo>
新版 (原生Gazebo传感器):
<gazebo reference="imu_link">
<sensor name="imu_sensor" type="imu">
<always_on>true</always_on>
<update_rate>100</update_rate>
<topic>imu</topic>
<imu>
<!-- noise configuration -->
</imu>
</sensor>
</gazebo>
关键差异:
<plugin> 标签<ros> 配置<topic> 指定话题名ros_gz_bridge 桥接src/robot_description_pkg/plugins/gazebo_sensor_camera_plugin.xacro
旧版:
<gazebo reference="camera_link">
<sensor type="depth" name="camera_sensor">
<plugin name="depth_camera" filename="libgazebo_ros_camera.so">
<frame_name>camera_optical_link</frame_name>
</plugin>
<always_on>true</always_on>
<update_rate>10</update_rate>
<camera name="camera">
<!-- camera configuration -->
</camera>
</sensor>
</gazebo>
新版:
<gazebo reference="camera_link">
<sensor type="depth_camera" name="camera_sensor">
<always_on>true</always_on>
<update_rate>10</update_rate>
<topic>camera</topic>
<camera name="camera">
<horizontal_fov>1.5009831567</horizontal_fov>
<image>
<width>800</width>
<height>600</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<!-- distortion configuration -->
</camera>
</sensor>
</gazebo>
关键差异:
depth → depth_camera<plugin> 配置<clip> 标签(近远平面)<topic> 指定话题README.md
旧版依赖:
sudo apt-get install ros-jazzy-gazebo-ros-pkgs # 不存在
sudo apt-get install ros-jazzy-gazebo-ros2-control # 不存在
新版依赖:
sudo apt-get install ros-jazzy-ros-gz # ROS-Gazebo桥接
sudo apt-get install ros-jazzy-gz-ros2-control # 新版控制接口
sudo apt-get install ros-jazzy-xacro
sudo apt-get install ros-jazzy-ros2-control
sudo apt-get install ros-jazzy-ros2-controllers
sudo apt-get install ros-jazzy-joint-state-publisher
sudo apt-get install ros-jazzy-joint-state-publisher-gui
问题: 新版Gazebo中经常出现时钟同步警告:
[WARN] No clock received, using time argument instead!
解决方案:
在所有节点中确保设置:
use_sim_time: true
在launch文件中:
parameters=[{
'use_sim_time': True
}]
$(find package_name) 语法说明: 在ROS2中,某些上下文仍然支持旧的$(find)语法,但建议迁移。
推荐写法:
# 在Python launch文件中
from ament_index_python.packages import get_package_share_directory
urdf_path = os.path.join(get_package_share_directory('pkg_name'), 'urdf', 'robot.urdf.xacro')
注意: 确保URDF文件头部包含正确的xacro命名空间:
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="robot_name">
| 方面 | Gazebo Classic | Gazebo Harmonic |
|---|---|---|
| 数据发布 | ROS插件直接发布 | Gazebo原生话题 |
| ROS集成 | 内置 | 需要桥接 |
| 配置复杂度 | 简单(一步) | 中等(两步) |
| 性能 | 一般 | 更好 |
# 桥接格式:/topic@ROS_Type[GZ_Type
bridge_node = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/laser_scan@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan',
'/camera@sensor_msgs/msg/Image[gz.msgs.Image',
]
)
硬件接口插件名称
<!-- 正确 -->
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
<!-- 错误 -->
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
控制器参数文件
controller_manager:
ros__parameters:
use_sim_time: true # 必须设置
update_rate: 30
接口定义
<joint name="wheel_joint">
<command_interface name="effort"/> <!-- 或 velocity, position -->
<state_interface name="position"/>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
# 推荐:使用事件处理器确保顺序
launch.actions.RegisterEventHandler(
event_handler=launch.event_handlers.OnProcessExit(
target_action=spawn_entity_node,
on_exit=[load_controller_node],
)
)
# 机器人描述参数
robot_description = ParameterValue(
Command(['xacro ', LaunchConfiguration('model')]),
value_type=str
)
# 调试时添加output='screen'
Node(
package='ros_gz_sim',
executable='create',
arguments=[...],
output='screen' # 显示详细输出
)
错误信息:
PackageNotFoundError: "package 'gazebo_ros' not found"
解决方案:
# 检查已安装的包
ros2 pkg list | grep gz
ros2 pkg list | grep gazebo
# 安装缺失的包
sudo apt-get install ros-jazzy-ros-gz
sudo apt-get install ros-jazzy-gz-ros2-control
错误信息:
Failed loading controller 'my_controller'
Couldn't parse params file: '--params-file -p'
可能原因:
解决方案:
# 检查参数文件
cat config/controller.yaml
# 验证控制器类型
ros2 control list_controller_types
# 手动加载测试
ros2 control load_controller my_controller
ros2 control set_controller_state my_controller active
症状:
ros2 topic list 没有相应输出检查清单:
验证方法:
# 检查Gazebo话题
gz topic -l
# 检查ROS话题
ros2 topic list
# 测试桥接
ros2 run ros_gz_bridge parameter_bridge /imu@sensor_msgs/msg/Imu[gz.msgs.IMU
可能原因:
调试步骤:
# 检查URDF有效性
check_urdf model.urdf
# 查看xacro处理后的URDF
xacro model.urdf.xacro > output.urdf
# 手动加载到Gazebo
gz sim -v 4 # 详细输出
# Gazebo命令行工具
gz sim --help
gz topic -l
gz model -l
# ROS2调试工具
ros2 topic list
ros2 node list
ros2 param list
ros2 control list_controllers
| 功能 | Gazebo Classic | Gazebo Harmonic |
|---|---|---|
| 仿真器 | gazebo_ros |
ros_gz_sim |
| 控制接口 | gazebo_ros2_control |
gz_ros2_control |
| 桥接 | 内置 | ros_gz_bridge |
| 消息 | gazebo_msgs |
ros_gz_interfaces |
| 图像工具 | 内置 | ros_gz_image |
# 启动仿真
ros2 launch <pkg> <launch_file>
# 检查话题
ros2 topic list
ros2 topic echo /imu
# 控制器管理
ros2 control list_controllers
ros2 control load_controller <name>
ros2 control switch_controllers --activate <name>
# Gazebo调试
gz sim -v 4
gz topic -l
gz topic -e -t /topic_name
本文档基于经验编写,持续更新中。