ROS机器人学习(四)--Gazebo物理仿真环境搭建

本文最后更新于:2022年5月29日 上午

1、配置机器人模型

1. 创建机器人模型文件

在mbot_description功能包的urdf文件夹下新建gazebo文件夹,创建模型文件mbot_base_gazebo.xacro:

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

<!-- PROPERTY LIST -->
<xacro:property name="M_PI" value="3.1415926"/>
<xacro:property name="base_mass" value="20" />
<xacro:property name="base_radius" value="0.16"/>
<xacro:property name="base_length" value="0.005"/>

<xacro:property name="wheel_mass" value="2" />
<xacro:property name="wheel_radius" value="0.032"/>
<xacro:property name="wheel_length" value="0.025"/>
<xacro:property name="wheel_joint_x" value="0.09"/>
<xacro:property name="wheel_joint_y" value="0.12"/>
<xacro:property name="wheel_joint_z" value="0.01"/>

<xacro:property name="caster_mass" value="0.5" />
<xacro:property name="caster_radius" value="0.01975"/> <!-- (wheel_radius + wheel_joint_z - base_length/2) / 2 -->
<xacro:property name="caster_joint_x" value="-0.12"/>

<!-- Defining the colors used in this robot -->
<material name="yellow">
<color rgba="1 0.4 0 1"/>
</material>
<material name="black">
<color rgba="0 0 0 0.95"/>
</material>
<material name="gray">
<color rgba="0.75 0.75 0.75 1"/>
</material>
<material name="white">
<color rgba="1 1 1 0.9" />
</material>

<!-- Macro for inertia matrix -->
<xacro:macro name="sphere_inertial_matrix" params="m r">
<inertial>
<mass value="${m}" />
<inertia ixx="${2*m*r*r/5}" ixy="0" ixz="0"
iyy="${2*m*r*r/5}" iyz="0"
izz="${2*m*r*r/5}" />
</inertial>
</xacro:macro>

<xacro:macro name="cylinder_inertial_matrix" params="m r h">
<inertial>
<mass value="${m}" />
<inertia ixx="${m*(3*r*r+h*h)/12}" ixy = "0" ixz = "0"
iyy="${m*(3*r*r+h*h)/12}" iyz = "0"
izz="${m*r*r/2}" />
</inertial>
</xacro:macro>

<!-- Macro for robot wheel -->
<xacro:macro name="wheel" params="prefix reflect">
<joint name="${prefix}_wheel_joint" type="continuous">
<origin xyz="${wheel_joint_x} ${reflect*wheel_joint_y} ${-wheel_joint_z}" rpy="0 0 0"/>
<parent link="base_link"/>
<child link="${prefix}_wheel_link"/>
<axis xyz="0 1 0"/>
</joint>
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
<material name="gray" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder radius="${wheel_radius}" length = "${wheel_length}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${wheel_mass}" r="${wheel_radius}" h="${wheel_length}" />
</link>

<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/Gray</material>
</gazebo>

<!-- Transmission is important to link the joints and the controller -->
<transmission name="${prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>



<xacro:macro name="mbot_base_gazebo">
<link name="base_footprint">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
</link>
<gazebo reference="base_footprint">
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${base_length/2 + caster_radius*2}" rpy="0 0 0" />
<parent link="base_footprint"/>
<child link="base_link" />
</joint>

<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}"/>
</geometry>
<material name="yellow" />
</visual>
<collision>
<origin xyz=" 0 0 0" rpy="0 0 0" />
<geometry>
<cylinder length="${base_length}" radius="${base_radius}"/>
</geometry>
</collision>
<cylinder_inertial_matrix m="${base_mass}" r="${base_radius}" h="${base_length}" />
</link>
<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>

<link name="back_caster_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<sphere radius="${caster_radius}" />
</geometry>
<material name="black" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="0 0 0"/>
<geometry>
<sphere radius="${caster_radius}" />
</geometry>
</collision>
<sphere_inertial_matrix m="${caster_mass}" r="${caster_radius}" />
</link>
<gazebo reference="back_caster_link">
<material>Gazebo/Black</material>
</gazebo>
<joint name="back_caster_joint" type="continuous">
<origin xyz="${caster_joint_x} 0 ${-(base_length/2 + caster_radius)}" rpy="0 0 0" />
<parent link="base_link" />
<child link="back_caster_link" />
<axis xyz="0 1 0" />
</joint>

<wheel prefix="left" reflect="-1"/>
<wheel prefix="right" reflect="1"/>

<!-- controller -->
<gazebo>
<plugin name="differential_drive_controller"
filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>${wheel_joint_y*2}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>
</xacro:macro>

</robot>

2. 模型文件解读

与上一篇文章的xacro模型相比较,主要有以下几点改变:

1)为link添加惯性参数和碰撞属性(以base_link为例)V3powQ.png
2)为link添加gazebo标签(以base_link为例)

1
2
3
<gazebo reference="base_link">
<material>Gazebo/Blue</material>
</gazebo>

3)为joint添加传动装置
这里我们给车轮添加传动装置,相当于给车轮添加电机。

1
2
3
4
5
6
7
8
9
10
11
<!-- Transmission is important to link the joints and the controller -->
<transmission name="${prefix}_wheel_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel_joint" >
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_wheel_joint_motor">
<hardwareInterface>hardware_interface/VelocityJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>

4)添加gazebo控制器插件

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
<!-- controller -->
<gazebo>
<plugin name="differential_drive_controller"
filename="libgazebo_ros_diff_drive.so">
<rosDebugLevel>Debug</rosDebugLevel>
<publishWheelTF>true</publishWheelTF>
<robotNamespace>/</robotNamespace>
<publishTf>1</publishTf>
<publishWheelJointState>true</publishWheelJointState>
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<legacyMode>true</legacyMode>
<leftJoint>left_wheel_joint</leftJoint>
<rightJoint>right_wheel_joint</rightJoint>
<wheelSeparation>${wheel_joint_y*2}</wheelSeparation>
<wheelDiameter>${2*wheel_radius}</wheelDiameter>
<broadcastTF>1</broadcastTF>
<wheelTorque>30</wheelTorque>
<wheelAcceleration>1.8</wheelAcceleration>
<commandTopic>cmd_vel</commandTopic>
<odometryFrame>odom</odometryFrame>
<odometryTopic>odom</odometryTopic>
<robotBaseFrame>base_footprint</robotBaseFrame>
</plugin>
</gazebo>

<robotNamespace>:机器人的命名空间。

<leftJoint>和<rightJoint>:左右轮转动的关节joint。

<wheelSeparation>和<wheelDiameter>:机器人模型的相关尺寸,在计算差速参数时需要用到。

<commandTopic>:控制器订阅的速度控制指令,生成全局命名时需要结合<robotNamespace>中设置的命名空间。

<odometryFrame>:里程计数据的参考坐标系,ROS中一般都命名为odom。

3. 在Gazebo中加载机器人模型

1)新建mbot_gazebo功能包:(记得修改packge.xml

1
catkin_create_pkg mbot_gazebo gazebo_plugins gazebo_ros gazebo_ros_control

2)新建launch文件夹,并新建启动文件view_mbot_gazebo_empty_world.launch:

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
<launch>

<!-- 设置launch文件的参数 -->
<arg name="paused" default="false"/>
<arg name="use_sim_time" default="true"/>
<arg name="gui" default="true"/>
<arg name="headless" default="false"/>
<arg name="debug" default="false"/>

<!-- 运行gazebo仿真环境 -->
<include file="$(find gazebo_ros)/launch/empty_world.launch">
<arg name="debug" value="$(arg debug)" />
<arg name="gui" value="$(arg gui)" />
<arg name="paused" value="$(arg paused)"/>
<arg name="use_sim_time" value="$(arg use_sim_time)"/>
<arg name="headless" value="$(arg headless)"/>
</include>

<!-- 加载机器人模型描述参数 -->
<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mbot_description)/urdf/gazebo/mbot_gazebo.xacro'" />

<!-- 运行joint_state_publisher节点,发布机器人的关节状态 -->
<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher" ></node>

<!-- 运行robot_state_publisher节点,发布tf -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen" >
<param name="publish_frequency" type="double" value="50.0" />
</node>

<!-- 在gazebo中加载机器人模型-->
<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen"
args="-urdf -model mbot -param robot_description"/>

</launch>

3)运行此launch文件即可打开Gazebo加载你的机器模型

1
roslaunch mbot_gazebo view_mbot_gazebo_empty_world.launch

V3pqWq.png


### 2、创建仿真环境 在Gazebo创建仿真环境有3种方法:

点击图标或命令行打开运行Gazebo。

第一种方法:直接添加环境模型

V3pOS0.png
添加完后,选择左上角“File->Save world as”保存你的创建的仿真环境。

第二种方法:使用Building Editor

点击Edit 选择Building Editor进入编辑模式,在这里你可以自己画出你想要的仿真环境。V3pbYn.png
创建好环境后,再次点击Edit,选择退出并保存。

3、开始仿真

1)启动仿真环境

1
roslaunch mbot_gazebo view_mbot_gazebo_play_ground.launch 

2)启动键盘控制

1
roslaunch mbot_teleop mbot_teleop.launch

现在你可以控制你的机器人模型在物理仿真中移动了。

V3pjyT.png

想要控制其他的机器人模型,只需要修改launch文件的“加载机器人模型描述参数”,指定你的模型路径即可。

传感器仿真

激光雷达传感器

启动仿真环境

1
roslaunch mbot_gazebo view_mbot_with_laser_gazebo.launch

打开rviz添加查看激光雷达仿真

1
rosrun rviz rviz

V3pXlV.png


ROS机器人学习(四)--Gazebo物理仿真环境搭建
https://kevinloongc.github.io/posts/64089.html
作者
Kevin Loongc
发布于
2019年4月27日
许可协议