Gazebo之Sensors简介
1. 源由
本章将学习如何将传感器添加到机器人仿真世界中。
- 典型的三种不同传感器:IMU传感器、接触传感器和激光雷达传感器。
- 同时,还将学习如何使用
gz launch
通过一个文件启动多个任务。
2. 初步准备
默认插件不会加载。因此,在添加传感器之前,首先需要添加一些逻辑上的默认设置,以便使用 GZ GUI:
<sdf version='1.9'>
<world name='demo'>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<!-- ... -->
测试资料:SnapLearnGazebo/lesson_02_sensor
3. 传感器
使用 moving_robot.sdf
作为基础SDF文件,创建一个新的文件 sensor_tutorial.sdf
,在上面逐步添加上述传感器。
3.1 IMU 传感器
惯性测量单元 (IMU) 输出三个轴 (X, Y, Z) 的角速度和三个轴上的线性加速度。
Step 1: 引用 IMU 传感器
在 标签下添加以下代码:
<plugin filename="gz-sim-imu-system"
name="gz::sim::systems::Imu">
</plugin>
Step 2: 添加 IMU 传感器
添加到机器人世界中:
- <always_on> 如果为 true,传感器将始终根据更新速率进行更新。
- <update_rate> 生成传感器数据的频率。
- 如果为 true,传感器将在 GUI 中可视化。
- 发布数据的主题名称。
注:并非所有传感器都支持所有标签。
<sensor name="imu_sensor" type="imu">
<always_on>1</always_on>
<update_rate>1</update_rate>
<visualize>true</visualize>
<topic>imu</topic>
</sensor>
Step 3: 读取 IMU 传感数据
- 在一个终端中运行世界并按下播放按钮:
$ gz sim sensor_tutorial.sdf
- 在另一个终端中执行以下命令:
$ gz topic -e -t /imu
- 使用键盘的向上键移动你的机器人前进,可以看到传感器值在变化。
$ gz topic -e -t /imu
header {
stamp {
nsec: 1000000
}
data {
key: "frame_id"
value: "vehicle_blue::chassis::imu_sensor"
}
data {
key: "seq"
value: "0"
}
}
entity_name: "vehicle_blue::chassis::imu_sensor"
orientation {
x: 2.1215887269564552e-22
y: 5.4613557001741309e-23
z: 4.2036654388084205e-24
w: 1
}
orientation_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
angular_velocity {
x: 4.24317745391291e-19
y: 1.0922711400348261e-19
z: 8.4073308776168415e-21
}
angular_velocity_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
linear_acceleration {
x: 3.5127917569011972e-18
y: -2.8126787673456782e-17
}
linear_acceleration_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
header {
stamp {
sec: 1
}
data {
key: "frame_id"
value: "vehicle_blue::chassis::imu_sensor"
}
data {
key: "seq"
value: "1"
}
}
entity_name: "vehicle_blue::chassis::imu_sensor"
orientation {
x: -3.1711735761273735e-06
y: 5.1765558419587438e-06
z: 0.0077879738067922165
w: 0.99996967325371
}
orientation_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
angular_velocity {
x: 6.3239137476902e-05
y: -9.01573735557911e-05
z: 6.8026775775727753e-10
}
angular_velocity_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
linear_acceleration {
x: 0.00023964047644863543
y: 0.00019414434201520824
z: 9.7991386189340943
}
linear_acceleration_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
header {
stamp {
sec: 2
}
data {
key: "frame_id"
value: "vehicle_blue::chassis::imu_sensor"
}
data {
key: "seq"
value: "2"
}
}
entity_name: "vehicle_blue::chassis::imu_sensor"
orientation {
x: -2.3117893552150796e-08
y: 2.9654079887270204e-06
z: 0.0077879344431916247
w: 0.99996967357431121
}
orientation_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
angular_velocity {
x: -2.643416560507971e-11
y: 5.5508724142631941e-06
z: 2.61864093623602e-13
}
angular_velocity_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
linear_acceleration {
x: -7.0848758728578524e-05
y: -1.1039375494702606e-09
z: 9.799992568914794
}
linear_acceleration_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
header {
stamp {
sec: 3
}
data {
key: "frame_id"
value: "vehicle_blue::chassis::imu_sensor"
}
data {
key: "seq"
value: "3"
}
}
entity_name: "vehicle_blue::chassis::imu_sensor"
orientation {
x: -2.3722197175311586e-08
y: 3.0429764124486936e-06
z: 0.0077879344081707427
w: 0.99996967357435085
}
orientation_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
angular_velocity {
x: 8.7327529922574356e-12
y: -5.277354213423571e-06
z: -2.817821160315417e-11
}
angular_velocity_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
linear_acceleration {
x: -5.4889792669568007e-05
y: -8.05116325338902e-10
z: 9.7999923870500609
}
linear_acceleration_covariance {
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
data: 0
}
3.2 Contact 传感器
接触传感器,这个传感器会在接触到其他物体时发出指示。
我们将构建一个障碍物(墙)并在其上添加接触传感器。如果机器人碰到障碍物,它将停止,从而防止机器人损坏自身。
Step 1: 构建障碍物
添加一堵墙:
<model name='wall'>
<static>true</static>
<pose>5 0 0 0 0 0</pose><!--pose relative to the world-->
<link name='box'>
<visual name='visual'>
<geometry>
<box>
<size>0.5 10.0 2.0</size>
</box>
</geometry>
<!--let's add color to our link-->
<material>
<ambient>0.0 0.0 1.0 1</ambient>
<diffuse>0.0 0.0 1.0 1</diffuse>
<specular>0.0 0.0 1.0 1</specular>
</material>
</visual>
<collision name='collision'>
<geometry>
<box>
<size>0.5 10.0 2.0</size>
</box>
</geometry>
</collision>
</link>
</model>
Step 2: 引入 contact 传感器
通过添加以下代码来定义接触传感器:
<plugin filename="gz-sim-contact-system"
name="gz::sim::systems::Contact">
</plugin>
Step 3: 将传感器链接到墙模型
将接触传感器添加到墙模型的箱体链接中:
<sensor name='sensor_contact' type='contact'>
<contact>
<collision>collision</collision>
</contact>
</sensor>
的定义很简单,我们只需定义传感器的名称和类型。
在 collision 中,我们定义箱体链接的碰撞名称为 collision。
Step 4: 添加 TouchPlugin事件
TouchPlugin 会在墙被触摸时发布(发送)一条消息。插件的标签如下:
- :将与我们的墙接触的对象,在我们的例子中是 vehicle_blue。
- :设置我们话题的命名空间,因此当机器人碰到墙时,它会向 /wall/touched 话题发送一条消息。
<plugin filename="gz-sim-touchplugin-system"
name="gz::sim::systems::TouchPlugin">
<target>vehicle_blue</target>
<namespace>wall</namespace>
<time>0.001</time>
<enabled>true</enabled>
</plugin>
Step 5: 简单测试
- 在一个终端中运行世界并按下播放按钮:
$ gz sim sensor_tutorial.sdf
- 在另一个终端中执行以下命令:
$ gz topic -e -t /wa