1 概述

Gazebo 是一个 高保真度的机器人仿真平台,用于在虚拟环境中模拟机器人和其与环境的交互行为.

2 安装

不同版本的安装方式不一样, 这里以 jazzy 为例.

gazebo 主要有 classic 和 Harmonic 两个版本, 我们安装后者.

特性 Gazebo Classic Gazebo Harmonic(或 Ignition Gazebo 系列)
📦 名称 gazebo ignition-gazebo / gz-sim
🧱 架构 单体架构(monolithic) 模块化(plugin-based、库分离)
🎮 GUI 内嵌在 gazebo 中 独立 GUI(gz-gui)
🌐 网络通信 ROS(直接集成) ZeroMQ、Ignition Transport(更模块化)
⚙️ 插件 ROS plugin 直连 ROS 需使用 bridge(如 ros_ign_bridgegz-ros2-control
🧪 状态 维护模式(Gazebo 11 是最后一个版本) 正式接替,持续开发
📅 生命周期 Gazebo 11 维护到 2025 Harmonic 是长期支持版本(LTS)
🛠️ 构建系统 CMake 更现代的 CMake + modular libs
1
2
3
4
5
6
7
8
9
sudo curl https://packages.osrfoundation.org/gazebo.gpg --output /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg

echo "deb [arch=$(dpkg --print-architecture) signed-by=/usr/share/keyrings/pkgs-osrf-archive-keyring.gpg] http://packages.osrfoundation.org/gazebo/ubuntu-stable $(lsb_release -cs) main" | sudo tee /etc/apt/sources.list.d/gazebo-stable.list > /dev/null

# 慢的话可以换成清华源
# sudo sed -i 's|http://packages.ros.org|https://mirrors.tuna.tsinghua.edu.cn|g' /etc/apt/sources.list.d/ros2.list
sudo apt-get update
sudo apt-get install gz-harmonic
sudo apt install ros-jazzy-gz-*

3 使用

这里给出一个仿真的模板, 这是 gazebo harmonic 版本的.

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
# gazebo_display.launch.py
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, ExecuteProcess, TimerAction
from launch.substitutions import LaunchConfiguration, Command
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterValue
from ament_index_python.packages import get_package_share_directory
import os

def generate_launch_description():
pkg_path = get_package_share_directory('my_robot_description')
default_model_path = os.path.join(pkg_path, 'urdf', 'robot.xacro')
default_world_path = os.path.join(pkg_path, 'worlds', 'nav_world.sdf')

declare_model = DeclareLaunchArgument(
name='model',
default_value=default_model_path,
description='Path to URDF/XACRO model'
)

robot_description_content = Command(['xacro ', LaunchConfiguration('model')])
robot_description = ParameterValue(robot_description_content, value_type=str)

gz_sim = ExecuteProcess(
cmd=['gz', 'sim', '-r', '-v', '4', default_world_path],
output='screen'
)

spawn_robot = TimerAction(
period=2.0,
actions=[
Node(
package='ros_gz_sim',
executable='create',
arguments=[
'-name', 'my_robot',
'-topic', 'robot_description',
'-x', '0', '-y', '0', '-z', '0.3'
],
output='screen'
)
]
)

return LaunchDescription([
declare_model,

Node(
package='robot_state_publisher',
executable='robot_state_publisher',
parameters=[{'robot_description': robot_description}],
output='screen'
),

gz_sim,
spawn_robot,
])

gazebo harmonic 不能向 classic 那样直接建立一个场景, 这里给出一个示例场景.

我们放在项目的 wrolds 目录下, 并在 CMakeLists.txt 中加入.

1
2
3
install(DIRECTORY worlds
DESTINATION share/${PROJECT_NAME}
)
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
# nav_world.sdf
<?xml version="1.0" ?>
<sdf version="1.7">
<world name="nav_world">

<!-- 基本光源 -->
<light name="sun" type="directional">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.1 0.1 0.1 1</specular>
<direction>-0.5 0.5 -1</direction>
</light>

<!-- 地面(自定义 plane,非 Fuel) -->
<model name="ground_plane">
<static>true</static>
<link name="ground_link">
<collision name="ground_collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>20 20</size>
</plane>
</geometry>
</collision>
<visual name="ground_visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>20 20</size>
</plane>
</geometry>
<material>
<ambient>0.5 0.5 0.5 1</ambient>
<diffuse>0.7 0.7 0.7 1</diffuse>
</material>
</visual>
</link>
</model>

<!-- 墙体(前) -->
<model name="wall_front">
<pose>2 0 0.5 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box><size>0.2 4 1</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>0.2 4 1</size></box>
</geometry>
<material>
<ambient>0.6 0.6 0.6 1</ambient>
</material>
</visual>
</link>
</model>

<!-- 墙体(右) -->
<model name="wall_right">
<pose>0 2 0.5 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box><size>4 0.2 1</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>4 0.2 1</size></box>
</geometry>
<material>
<ambient>0.4 0.8 0.4 1</ambient>
</material>
</visual>
</link>
</model>

<!-- 障碍 -->
<model name="box_obstacle">
<pose>1 1 0.25 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box><size>0.5 0.5 0.5</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>0.5 0.5 0.5</size></box>
</geometry>
<material>
<ambient>1 0.3 0.3 1</ambient>
</material>
</visual>
</link>
</model>

<!-- 机器人出生点 -->
<model name="robot_spawn">
<pose>0 0 0.01 0 0 0</pose>
<static>true</static>
<link name="spawn_link">
<visual name="dummy">
<geometry><box><size>0.001 0.001 0.001</size></box></geometry>
</visual>
</link>
</model>

</world>
</sdf>

4 标签

4.1 摩擦力设置

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
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro">

<xacro:macro name="mul_wheel" params="name parent xyz">

<xacro:property name="wheel_mass" value="0.1"/>
<xacro:property name="wheel_radius" value="0.03"/>

<link name="${name}_link">
<visual>
<geometry>
<sphere radius="${wheel_radius}"/>
</geometry>
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
<material name="gray">
<color rgba="0.4 0.4 0.4 1"/>
</material>
</visual>
<collision>
<geometry>
<sphere radius="${wheel_radius}"/>
</geometry>
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
</collision>
<inertial>
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
<mass value="${wheel_mass}"/>
<inertia ixx="1e-5" ixy="0.0" ixz="0.0"
iyy="1e-5" iyz="0.0"
izz="1e-5"/>
</inertial>
</link>

<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}_link"/>
<origin xyz="${xyz}" rpy="0 0 0"/>
</joint>

<!-- 新增 -->
<gazebo reference="${name}_link">
<mu1>0.01</mu1>
<mu2>0.01</mu2>
<material>Gazebo/Grey</material>
</gazebo>
<!-- 新增 -->
</xacro:macro>


<xacro:macro name="wheel" params="name parent xyz">
<xacro:property name="wheel_mass" value="0.3"/>
<xacro:property name="inertia_ixx" value="${0.5 * wheel_mass * wheel_radius * wheel_radius}"/>
<xacro:property name="inertia_iyy" value="${0.5 * wheel_mass * wheel_radius * wheel_radius}"/>
<xacro:property name="inertia_izz" value="${0.5 * wheel_mass * wheel_radius * wheel_radius}"/>

<link name="${name}_link">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<origin xyz="0 0 ${wheel_radius}" rpy="1.5708 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
<origin xyz="0 0 ${wheel_radius}" rpy="1.5708 0 0"/>
<material name="black">
<color rgba="0 0 0 1"/>
</material>
</collision>
<inertial>
<origin xyz="0 0 ${wheel_radius}" rpy="0 0 0"/>
<mass value="${wheel_mass}"/>
<inertia
ixx="${inertia_ixx}" ixy="0.0" ixz="0.0"
iyy="${inertia_iyy}" iyz="0.0"
izz="${inertia_izz}"/>
</inertial>
</link>

<joint name="${name}_joint" type="continuous">
<parent link="${parent}"/>
<child link="${name}_link"/>
<origin xyz="${xyz}" rpy="0 0 0"/>
<axis xyz="0 1 0"/>
</joint>

<!-- 新增 -->
<gazebo reference="${name}_link">
<mu1>20.0</mu1>
<mu2>20.0</mu2>
<material>Gazebo/Black</material>
</gazebo>
<!-- 新增 -->

</xacro:macro>

</robot>

5 插件

对于 harmonic 所有版本, 我们进行仿真之前都需要区对应的 world 文件里加入对应的 plugin.

5.1 两轮差速插件

示例, 需要使用修改参数即可.

alt text

参数名 示例值 单位 说明
left_joint left_wheel_joint - 左轮 joint 名称,需与 <joint> 中定义一致
right_joint right_wheel_joint - 右轮 joint 名称,需与 <joint> 中定义一致
wheel_separation 0.4 米(m) 左右轮中心间距,通常等于底盘宽度
wheel_diameter 0.2 米(m) 车轮直径
max_torque 20 牛·米(Nm) 每个轮子最大扭矩限制(控制电机强度)
max_accel 1.0 米/秒²(m/s²) 轮子的最大线性加速度
update_rate 30 Hz 插件刷新频率,越高越精细但计算负担也越大
odom_frame odom - 发布的里程计参考坐标系名称,通常为 odom
base_frame base_footprint - 机器人底部坐标系,通常绑定在底盘中心
publish_odom true / false 布尔 是否通过 ROS 发布 /odom 消息
publish_odom_tf true / false 布尔 是否广播 odom 到 base 的 TF 变换
publish_wheel_tf true / false 布尔 是否广播轮子 joint 的 TF(调试用)

下面作为一个模板示例.

项目 Gazebo Classic Gazebo Sim (Ignition)
插件文件 libgazebo_ros_diff_drive.so gz-sim-diff-drive-system
插件命名空间 ROS 接口(gazebo_ros) Gazebo 内置 C++ 系统(gz::sim::systems)
ROS 集成方式 gazebo_ros_pkgs 提供 ros_gz 桥接话题
适用 ROS 版本 ROS 1 / ROS 2 <= Humble ROS 2 Rolling / Jazzy / Iron

humble 版本.

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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- 差速控制插件宏,带参数可复用 -->
<xacro:macro name="gazebo_control_plugin" params="
left_joint right_joint
wheel_separation wheel_diameter
max_torque max_accel
update_rate
odom_frame base_frame
publish_odom publish_odom_tf publish_wheel_tf
">

<gazebo>
<plugin name="diff_drive_controller" filename="libgazebo_ros_diff_drive.so">

<!-- ROS 命名空间与话题重映射 -->
<ros>
<namespace>/</namespace>
<remapping>cmd_vel:=cmd_vel</remapping>
<remapping>odom:=odom</remapping>
</ros>

<!-- 插件刷新频率 -->
<update_rate>${update_rate}</update_rate>

<!-- 车轮 joint 名 -->
<left_joint>${left_joint}</left_joint>
<right_joint>${right_joint}</right_joint>

<!-- 差速运动学参数 -->
<wheel_separation>${wheel_separation}</wheel_separation>
<wheel_diameter>${wheel_diameter}</wheel_diameter>

<!-- 扭矩/加速度限制 -->
<max_wheel_torque>${max_torque}</max_wheel_torque>
<max_wheel_acceleration>${max_accel}</max_wheel_acceleration>

<!-- 里程计与 TF -->
<publish_odom>${publish_odom}</publish_odom>
<publish_odom_tf>${publish_odom_tf}</publish_odom_tf>
<publish_wheel_tf>${publish_wheel_tf}</publish_wheel_tf>

<odometry_frame>${odom_frame}</odometry_frame>
<robot_base_frame>${base_frame}</robot_base_frame>
</plugin>
</gazebo>

</xacro:macro>
</robot>

我们可以直接使用.

1
2
3
4
5
6
7
8
9
10
11
12
13
<xacro:gazebo_control_plugin
left_joint="left_wheel_joint"
right_joint="right_wheel_joint"
wheel_separation="0.4"
wheel_diameter="0.2"
max_torque="15"
max_accel="2.0"
update_rate="50"
odom_frame="odom"
base_frame="base_footprint"
publish_odom="true"
publish_odom_tf="true"
publish_wheel_tf="false"/>

harmonic 版本.

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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- Gazebo Sim 差速驱动插件(gz::sim::systems::DiffDrive) -->
<xacro:macro name="gazebo_control_plugin" params="
left_joint right_joint
wheel_separation wheel_radius
max_accel
odom_topic cmd_vel_topic
odom_frame base_frame
odom_pub_freq
">

<gazebo>
<plugin name="gz::sim::systems::DiffDrive" filename="gz-sim-diff-drive-system">

<!-- 车轮 joint 名 -->
<left_joint>${left_joint}</left_joint>
<right_joint>${right_joint}</right_joint>

<!-- 运动学参数 -->
<wheel_separation>${wheel_separation}</wheel_separation>
<wheel_radius>${wheel_radius}</wheel_radius>
<max_linear_acceleration>${max_accel}</max_linear_acceleration>

<!-- ROS 接口(通过 ros_gz_bridge 使用) -->
<topic>${cmd_vel_topic}</topic>
<odom_topic>${odom_topic}</odom_topic>

<!-- TF 设置 -->
<frame_id>${odom_frame}</frame_id>
<child_frame_id>${base_frame}</child_frame_id>

<!-- 发布频率 -->
<odom_publisher_frequency>${odom_pub_freq}</odom_publisher_frequency>
<tf_topic>/tf</tf_topic>

</plugin>

<plugin filename="gz-sim-joint-state-publisher-system" name="gz::sim::systems::JointStatePublisher">
<topic>joint_states</topic>
<joint_name>${left_joint}</joint_name>
<joint_name>${right_joint}</joint_name>
</plugin>
</gazebo>

</xacro:macro>
</robot>
1
2
3
4
5
6
7
8
9
10
11
<xacro:gazebo_control_plugin
left_joint="left_wheel_joint"
right_joint="right_wheel_joint"
wheel_separation="0.4"
wheel_radius="0.1"
max_accel="0.033"
cmd_vel_topic="cmd_vel"
odom_topic="odom"
odom_frame="odom"
base_frame="base_footprint"
odom_pub_freq="30"/>

注意的是, 要想通过 ros2 topic 命令控制小车, 需要桥接 ros2 和 gazebo 的话题.

打开 Terminal 1 运行.

1
ros2 run ros_gz_bridge parameter_bridge /cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist

打开 Terminal 2 运行.

1
2
3
4
# 示例
ros2 topic pub -r 10 /cmd_vel geometry_msgs/msg/Twist '{linear: {x: 0.2}, angular: {z: 0.5}}'
# 或者
ros2 run teleop_twist_keyboard teleop_twist_keyboard

我们当然也可以使用 gazebo 原生的命令, 就不用桥接话题了.

1
2
3
gz topic -e -t /keyboard/keypress
# 或者
gz topic -t /cmd_vel -m gz.msgs.Twist -p '{linear: {x: 0.2}, angular: {z: 0.5}}'

5.2 激光雷达

classic 版本.

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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="gazebo_sensor_plugin">
<gazebo reference="laser_link">
<sensor name="laserscan" type="ray">
<plugin name="laserscan" 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>
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>5</update_rate>
<pose>0 0 0 0 0 0</pose>
<!-- 激光传感器配置 -->
<ray>
<!-- 设置扫描范围 -->
<scan>
<horizontal>
<samples>360</samples>
<resolution>1.000000</resolution>
<min_angle>0.000000</min_angle>
<max_angle>6.280000</max_angle>
</horizontal>
</scan>
<!-- 设置扫描距离 -->
<range>
<min>0.120000</min>
<max>8.0</max>
<resolution>0.015000</resolution>
</range>
<!-- 设置噪声 -->
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</ray>
</sensor>
</gazebo>
</xacro:macro>
</robot>

harmonic 版本.

直接内嵌到 link 里.

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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:macro name="lidar_sensor" params="name parent xyz rpy">

<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}_link"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>

<link name="${name}_link">
<visual>
<origin xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
<material name="laser_material">
<color rgba="0.13 0.13 0.13 1.0"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0"/>
<geometry>
<cylinder length="0.04" radius="0.05"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.1"/>
<inertia
ixx="1e-5" ixy="0" ixz="0"
iyy="1e-5" iyz="0"
izz="1e-5"/>
</inertial>
</link>

<gazebo reference="${name}_link">
<sensor name="${name}_link" type="gpu_lidar">
<pose> 0 0 0 0 0 0 </pose>
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>10</update_rate>
<topic>scan</topic>
<gz_frame_id>${name}_link</gz_frame_id>
<lidar>
<scan>
<horizontal>
<samples>360</samples>
<min_angle>-3.14</min_angle>
<max_angle>3.14</max_angle>
</horizontal>
<vertical>
<samples>1</samples>
<resolution>0.01</resolution>
<min_angle>0</min_angle>
<max_angle>0</max_angle>
</vertical>
</scan>
<range>
<min>0.3</min>
<max>12</max>
</range>
</lidar>
</sensor>
</gazebo>

</xacro:macro>

</robot>

5.3 IMU

harmonic 版本.

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
<xacro:macro name="imu_sensor" params="
parent_link
child_link
xyz
rpy
update_rate
topic">

<link name="${child_link}">
<inertial>
<mass>0.01</mass>
<inertia>
<ixx>0.0001</ixx><ixy>0</ixy><ixz>0</ixz>
<iyy>0.0001</iyy><iyz>0</iyz><izz>0.0001</izz>
</inertia>
</inertial>
</link>

<joint name="${child_link}_fixed_joint" type="fixed">
<parent link="${parent_link}"/>
<child link="${child_link}"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>

<gazebo reference="${child_link}">
<sensor name="${child_link}" type="imu">
<always_on>1</always_on>
<update_rate>${update_rate}</update_rate>
<visualize>true</visualize>
<topic>${topic}</topic>
</sensor>
</gazebo>
</xacro:macro>

5.4 深度相机

harmonic 版本.

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
<xacro:macro name="imu_sensor" params="
name
parent
xyz
rpy">

<link name="${name}_link">
<visual>
<origin xyz="${xyz}" rpy="${rpy}"/>
<geometry>
<box size="0.01 0.01 0.01"/>
</geometry>
<material name="${name}_material">
<color rgba="0.63 0.63 0.63 1.0"/>
</material>
</visual>
<inertial>
<mass value="0.01"/>
<inertia
ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>
</link>

<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}_link"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>

<gazebo reference="${name}_link">
<sensor name="${name}_link" type="imu">
<topic>imu</topic>
<update_rate>1</update_rate>
<always_on>1</always_on>
<visualize>true</visualize>
<gz_frame_id>${name}_link</gz_frame_id>
</sensor>
</gazebo>
</xacro:macro>

<xacro:macro name="depth_camera" params="
name
parent
xyz
rpy">

<link name="${name}_link">
<inertial>
<mass value="0.05"/>
<inertia
ixx="0.0001" ixy="0.0" ixz="0.0"
iyy="0.0001" iyz="0.0" izz="0.0001"/>
</inertial>

<visual>
<geometry>
<box size="0.05 0.4 0.04"/>
</geometry>
<material name="CameraGray">
<color rgba="0.5 0.5 0.5 1.0"/>
</material>
</visual>

<collision>
<geometry>
<box size="0.05 0.4 0.04" />
</geometry>
</collision>
</link>

<joint name="${name}_joint" type="fixed">
<parent link="${parent}"/>
<child link="${name}_link"/>
<origin xyz="${xyz}" rpy="${rpy}"/>
</joint>

<gazebo reference="${name}_link">
<sensor name="${name}_link" type="rgbd_camera">
<always_on>true</always_on>
<visualize>true</visualize>
<update_rate>100</update_rate>
<topic>camera</topic>
<gz_frame_id>${name}_link</gz_frame_id>
<camera name="${name}_link">
<camera_info_topic>camera/camera_info</camera_info_topic>
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>800</width>
<height>600</height>
<format>R8G8B8</format>
</image>
<clip>
<near>0.1</near>
<far>100</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
</sensor>
</gazebo>

</xacro:macro>

alt text

6 常见桥接配置示例

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
# bridge.launch.py
from launch import LaunchDescription
from launch_ros.actions import Node
import os

from ament_index_python.packages import get_package_share_directory

def generate_launch_description():
config_path = os.path.join(
get_package_share_directory('my_robot_description'),
'config',
'bridge_config.yaml'
)

return LaunchDescription([
Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
"--ros-args",
"-p",
f"config_file:={config_path}",
],
output='screen'
)
])
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
# bridge_config.yaml
# gz topic published by the simulator core
- ros_topic_name: "clock"
gz_topic_name: "clock"
ros_type_name: "rosgraph_msgs/msg/Clock"
gz_type_name: "gz.msgs.Clock"
direction: GZ_TO_ROS

# gz topic published by JointState plugin
- ros_topic_name: "joint_states"
gz_topic_name: "joint_states"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
direction: GZ_TO_ROS

# gz topic published by DiffDrive plugin
- ros_topic_name: "odom"
gz_topic_name: "odom"
ros_type_name: "nav_msgs/msg/Odometry"
gz_type_name: "gz.msgs.Odometry"
direction: GZ_TO_ROS

# gz topic published by DiffDrive plugin
- ros_topic_name: "tf"
gz_topic_name: "tf"
ros_type_name: "tf2_msgs/msg/TFMessage"
gz_type_name: "gz.msgs.Pose_V"
direction: GZ_TO_ROS

# # gz topic subscribed to by DiffDrive plugin
- ros_topic_name: "cmd_vel"
gz_topic_name: "cmd_vel"
ros_type_name: "geometry_msgs/msg/Twist"
gz_type_name: "gz.msgs.Twist"
direction: ROS_TO_GZ

# gz topic published by IMU plugin
- ros_topic_name: "imu"
gz_topic_name: "imu"
ros_type_name: "sensor_msgs/msg/Imu"
gz_type_name: "gz.msgs.IMU"
direction: GZ_TO_ROS

# gz topic published by Sensors plugin
- ros_topic_name: "scan"
gz_topic_name: "scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS

# gz topic published by Sensors plugin (Camera)
- ros_topic_name: "camera/camera_info"
gz_topic_name: "camera/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS

- ros_topic_name: "/camera/image"
gz_topic_name: "/camera/image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/camera/depth_image"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS

- topic_name: "/camera/points"
ros_type_name: "sensor_msgs/msg/PointCloud2"
gz_type_name: "gz.msgs.PointCloudPacked"
direction: GZ_TO_ROS

7 References