Using ros_gz_bridge#
Added in version Jazzy: This section.
Warning
This topic is under construction and this might not even be its final form. Please feel free to open an issue if you spot any typos or other problems.
See also
Official documentation: https://docs.ros.org/en/jazzy/p/ros_gz_bridge/
We have seen how to see internal Gazebo topics through the command line. This is not yet very useful to us, because we want to be able to integrate Gazebo with our own, custom ROS2 nodes.
The idea is to map Gazebo topics into ROS2 topics. This is where ros_gz_bridge comes in.
Each Gazebo message must be paired with a correct ROS2 message if you want to access these outside Gazebo. The file ros_gz_bridge/README.md in the official documentation shows the mappings.
Here is the current table.
The following message types can be bridged for topics:
| ROS type | Gazebo Transport Type |
| ---------------------------------------------- | :------------------------------: |
| actuator_msgs/msg/Actuators | gz.msgs.Actuators |
| builtin_interfaces/msg/Time | gz.msgs.Time |
| geometry_msgs/msg/Point | gz.msgs.Vector3d |
| geometry_msgs/msg/Pose | gz.msgs.Pose |
| geometry_msgs/msg/PoseArray | gz.msgs.Pose_V |
| geometry_msgs/msg/PoseStamped | gz.msgs.Pose |
| geometry_msgs/msg/PoseWithCovariance | gz.msgs.PoseWithCovariance |
| geometry_msgs/msg/PoseWithCovarianceStamped | gz.msgs.PoseWithCovariance |
| geometry_msgs/msg/Quaternion | gz.msgs.Quaternion |
| geometry_msgs/msg/Transform | gz.msgs.Pose |
| geometry_msgs/msg/TransformStamped | gz.msgs.Pose |
| geometry_msgs/msg/Twist | gz.msgs.Twist |
| geometry_msgs/msg/TwistStamped | gz.msgs.Twist |
| geometry_msgs/msg/TwistWithCovariance | gz.msgs.TwistWithCovariance |
| geometry_msgs/msg/TwistWithCovarianceStamped | gz.msgs.TwistWithCovariance |
| geometry_msgs/msg/Vector3 | gz.msgs.Vector3d |
| geometry_msgs/msg/Wrench | gz.msgs.Wrench |
| geometry_msgs/msg/WrenchStamped | gz.msgs.Wrench |
| gps_msgs/msg/GPSFix | gz.msgs.NavSat |
| marine_acoustic_msgs/msg/Dvl | gz.msgs.DVLVelocityTracking |
| nav_msgs/msg/Odometry | gz.msgs.Odometry |
| nav_msgs/msg/Odometry | gz.msgs.OdometryWithCovariance |
| rcl_interfaces/msg/ParameterValue | gz.msgs.Any |
| ros_gz_interfaces/msg/Altimeter | gz.msgs.Altimeter |
| ros_gz_interfaces/msg/Contact | gz.msgs.Contact |
| ros_gz_interfaces/msg/Contacts | gz.msgs.Contacts |
| ros_gz_interfaces/msg/Dataframe | gz.msgs.Dataframe |
| ros_gz_interfaces/msg/Entity | gz.msgs.Entity |
| ros_gz_interfaces/msg/EntityWrench | gz.msgs.EntityWrench |
| ros_gz_interfaces/msg/Float32Array | gz.msgs.Float_V |
| ros_gz_interfaces/msg/GuiCamera | gz.msgs.GUICamera |
| ros_gz_interfaces/msg/JointWrench | gz.msgs.JointWrench |
| ros_gz_interfaces/msg/Light | gz.msgs.Light |
| ros_gz_interfaces/msg/LogicalCameraImage | gz.msgs.LogicalCameraImage |
| ros_gz_interfaces/msg/LogPlaybackStatistics | gz.msgs.LogPlaybackStatistics |
| ros_gz_interfaces/msg/ParamVec | gz.msgs.Param |
| ros_gz_interfaces/msg/ParamVec | gz.msgs.Param_V |
| ros_gz_interfaces/msg/SensorNoise | gz.msgs.SensorNoise |
| ros_gz_interfaces/msg/StringVec | gz.msgs.StringMsg_V |
| ros_gz_interfaces/msg/TrackVisual | gz.msgs.TrackVisual |
| ros_gz_interfaces/msg/VideoRecord | gz.msgs.VideoRecord |
| ros_gz_interfaces/msg/WorldStatistics | gz.msgs.WorldStatistics |
| rosgraph_msgs/msg/Clock | gz.msgs.Clock |
| sensor_msgs/msg/BatteryState | gz.msgs.BatteryState |
| sensor_msgs/msg/CameraInfo | gz.msgs.CameraInfo |
| sensor_msgs/msg/FluidPressure | gz.msgs.FluidPressure |
| sensor_msgs/msg/Image | gz.msgs.Image |
| sensor_msgs/msg/Imu | gz.msgs.IMU |
| sensor_msgs/msg/JointState | gz.msgs.Model |
| sensor_msgs/msg/Joy | gz.msgs.Joy |
| sensor_msgs/msg/LaserScan | gz.msgs.LaserScan |
| sensor_msgs/msg/MagneticField | gz.msgs.Magnetometer |
| sensor_msgs/msg/NavSatFix | gz.msgs.NavSat |
| sensor_msgs/msg/PointCloud2 | gz.msgs.PointCloudPacked |
| sensor_msgs/msg/Range | gz.msgs.LaserScan |
| std_msgs/msg/Bool | gz.msgs.Boolean |
| std_msgs/msg/ColorRGBA | gz.msgs.Color |
| std_msgs/msg/Empty | gz.msgs.Empty |
| std_msgs/msg/Float32 | gz.msgs.Float |
| std_msgs/msg/Float64 | gz.msgs.Double |
| std_msgs/msg/Header | gz.msgs.Header |
| std_msgs/msg/Int32 | gz.msgs.Int32 |
| std_msgs/msg/String | gz.msgs.StringMsg |
| std_msgs/msg/UInt32 | gz.msgs.UInt32 |
| tf2_msgs/msg/TFMessage | gz.msgs.Pose_V |
| trajectory_msgs/msg/JointTrajectory | gz.msgs.JointTrajectory |
| vision_msgs/msg/Detection2D | gz.msgs.AnnotatedAxisAligned2DBox |
| vision_msgs/msg/Detection2DArray | gz.msgs.AnnotatedAxisAligned2DBox_V |
| vision_msgs/msg/Detection3D | gz::msgs::AnnotatedOriented3DBox |
| vision_msgs/msg/Detection3DArray | gz::msgs::AnnotatedOriented3DBox_V |
And the following for services:
Important
Some of these messages are part of the package ros_gz_interfaces. You can see more details about these
in the official repository.
We will be using mostly parameter_bridge, which is part of ros_gz_bridge to make these connections.
More information about the tool can be obtained with the help command.
ros2 run ros_gz_bridge parameter_bridge -h
To summarise the output, it is expected that we run
ros2 run ros_gz_bridge parameter_bridge
<Gazebo Topic>@<ROS Type>@<Gazebo Transport Type>
Using the logic above, we have that
<Gazebo Topic>defined for the entity on Gazebo and can be obtained withgz topic -l.We can find
<Gazebo Transport Type>withgz topic -i --topic <Gazebo Topic>.Lastly, we check the pairing table and see what
<ROS Type>matches the<Gazebo Transport Type>.The second @ means a bidirectional bridge. It can also be [ or ] to indicate a single direction. Some official examples are relatively lax with this rule.
Let’s see some examples.
Sensors#
See also
Official documentation: https://gazebosim.org/docs/harmonic/sensors/
Simulated sensor information is becoming evermore useful. In simulators, one of the main aspects making them useful will be our ability to obtain their data through ROS2. Cameras are likely to be the most common, but other sensors, such as lidars, are frequently used.
For each of these subsections, suppose that we have the sensors_demo.sdf scene always open. Don’t forget to
start the simulation as well!
gz sim sensors_demo.sdf
Note
Sensor information will only start to be published after the simulation is started in Gazebo.
gz.msgs.Image#
In a previous section, we have seen that the Gazebo topic /rgbd_camera/image exists and has
transport type gz.msgs.Image. Looking at the pairing table, we notice that the pairing ROS2 message
type is sensor_msgs/msg/Image.
We can run, therefore in one terminal, the following command.
ros2 run ros_gz_bridge \
parameter_bridge \
/rgbd_camera/image@sensor_msgs/msg/Image[gz.msgs.Image
To show the images, we can use rqt_image_view. Notice that the internal Gazebo topic name will be replicated into a ROS2 topic with the same name.
ros2 run rqt_image_view rqt_image_view /rgbd_camera/image
This will show the image obtained from Gazebo in rqt_image_view, effectively showing that these two are paired.
Exercises
Can you do the same for the /depth_camera or /thermal_camera internal Gazebo topic available in the same scene?
What steps would you take to show the images available in Gazebo into rqt_image_view?
gz.msgs.LaserScan#
We have already listed the Gazebo topics for this scene, so we know that there is a topic called
/lidar. We can obtain the related information with the following command.
gz topic -i --topic /lidar
This will output the following.
Publishers [Address, Message Type]:
tcp://172.16.191.128:40679, gz.msgs.LaserScan
No subscribers on topic [/lidar]
By looking at the pairing table, we find that gz.msgs.LaserScan should be paired with a sensor_msgs/msg/LaserScan.
Therefore, we can run the bridge as follows.
ros2 run ros_gz_bridge \
parameter_bridge \
/lidar@sensor_msgs/msg/LaserScan[gz.msgs.LaserScan
One convenient way to visualise this messages is through rviz2. We can do so as follows.
ros2 run rviz2 rviz2 -f camera_with_lidar/link/gpu_lidar
Note
We are starting rviz2 with the reference frame camera_with_lidar/link/gpu_lidar because that is
the frame shown in the topic /lidar.
We can then define the proper rviz2 view so be able to visualise the laser scan results.
.
.
Getting pose information#
One important aspect of entities in any simulation is their pose. We must be able to obtain poses to define the behavior of our robots. For instance, if a box in a simulation moves, the controller might need this information to define evasive maneuvers.
The most basic manner to be able to obtain the pose of an entity in Gazebo from an external program is to add
the following to each model, in the .sdf scene.
<plugin
filename="gz-sim-pose-publisher-system"
name="gz::sim::systems::PosePublisher">
<publish_link_pose>false</publish_link_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>true</publish_nested_model_pose>
</plugin>
Note
Settings will vary for more advanced use, but for basic shapes this will be enough.
To show how this works, let us create a folder for our modified shapes.sdf scene.
mkdir -p ~/gazebo_tutorial_workspace/scenes
cd ~/gazebo_tutorial_workspace/scenes
In this case, the file is quite large, so I suggest downloading shapes_with_pose_publisher.sdf and adding it to the folder above.
shapes_with_pose_publisher.sdf
Contents of shapes_with_pose_publisher.sdf
You will note that this is simply the default shapes.sdf with the plugin added to each entity.
1<?xml version="1.0" ?>
2<sdf version="1.11">
3 <!--
4 Try moving a model using the command in the following CDATA block::
5 -->
6 <![CDATA[
7 gz service -s /world/shapes/set_pose \
8 --reqtype gz.msgs.Pose --reptype gz.msgs.Boolean \
9 --timeout 300 --req 'name: "box", position: {z: 5.0}'
10 ]]>
11 <world name="shapes_with_pose_publisher">
12
13 <scene>
14 <ambient>1.0 1.0 1.0</ambient>
15 <background>0.8 0.8 0.8</background>
16 </scene>
17
18 <light type="directional" name="sun">
19 <cast_shadows>true</cast_shadows>
20 <pose>0 0 10 0 0 0</pose>
21 <diffuse>0.8 0.8 0.8 1</diffuse>
22 <specular>0.2 0.2 0.2 1</specular>
23 <attenuation>
24 <range>1000</range>
25 <constant>0.9</constant>
26 <linear>0.01</linear>
27 <quadratic>0.001</quadratic>
28 </attenuation>
29 <direction>-0.5 0.1 -0.9</direction>
30 </light>
31
32 <model name="ground_plane">
33 <static>true</static>
34 <link name="link">
35 <collision name="collision">
36 <geometry>
37 <plane>
38 <normal>0 0 1</normal>
39 <size>100 100</size>
40 </plane>
41 </geometry>
42 </collision>
43 <visual name="visual">
44 <geometry>
45 <plane>
46 <normal>0 0 1</normal>
47 <size>100 100</size>
48 </plane>
49 </geometry>
50 <material>
51 <ambient>0.8 0.8 0.8 1</ambient>
52 <diffuse>0.8 0.8 0.8 1</diffuse>
53 <specular>0.8 0.8 0.8 1</specular>
54 </material>
55 </visual>
56 </link>
57 </model>
58
59 <model name="box">
60 <pose>0 0 0.5 0 0 0</pose>
61 <link name="box_link">
62 <inertial>
63 <inertia>
64 <ixx>0.16666</ixx>
65 <ixy>0</ixy>
66 <ixz>0</ixz>
67 <iyy>0.16666</iyy>
68 <iyz>0</iyz>
69 <izz>0.16666</izz>
70 </inertia>
71 <mass>1.0</mass>
72 </inertial>
73 <collision name="box_collision">
74 <geometry>
75 <box>
76 <size>1 1 1</size>
77 </box>
78 </geometry>
79 </collision>
80
81 <visual name="box_visual">
82 <geometry>
83 <box>
84 <size>1 1 1</size>
85 </box>
86 </geometry>
87 <material>
88 <ambient>1 0 0 1</ambient>
89 <diffuse>1 0 0 1</diffuse>
90 <specular>1 0 0 1</specular>
91 </material>
92 </visual>
93 </link>
94
95 <plugin
96 filename="gz-sim-pose-publisher-system"
97 name="gz::sim::systems::PosePublisher">
98 <publish_link_pose>false</publish_link_pose>
99 <publish_collision_pose>false</publish_collision_pose>
100 <publish_visual_pose>false</publish_visual_pose>
101 <publish_nested_model_pose>true</publish_nested_model_pose>
102 </plugin>
103
104 </model>
105
106 <model name="cylinder">
107 <pose>0 -1.5 0.5 0 0 0</pose>
108 <link name="cylinder_link">
109 <inertial>
110 <inertia>
111 <ixx>0.1458</ixx>
112 <ixy>0</ixy>
113 <ixz>0</ixz>
114 <iyy>0.1458</iyy>
115 <iyz>0</iyz>
116 <izz>0.125</izz>
117 </inertia>
118 <mass>1.0</mass>
119 </inertial>
120 <collision name="cylinder_collision">
121 <geometry>
122 <cylinder>
123 <radius>0.5</radius>
124 <length>1.0</length>
125 </cylinder>
126 </geometry>
127 </collision>
128
129 <visual name="cylinder_visual">
130 <geometry>
131 <cylinder>
132 <radius>0.5</radius>
133 <length>1.0</length>
134 </cylinder>
135 </geometry>
136 <material>
137 <ambient>0 1 0 1</ambient>
138 <diffuse>0 1 0 1</diffuse>
139 <specular>0 1 0 1</specular>
140 </material>
141 </visual>
142 </link>
143
144 <plugin
145 filename="gz-sim-pose-publisher-system"
146 name="gz::sim::systems::PosePublisher">
147 <publish_link_pose>false</publish_link_pose>
148 <publish_collision_pose>false</publish_collision_pose>
149 <publish_visual_pose>false</publish_visual_pose>
150 <publish_nested_model_pose>true</publish_nested_model_pose>
151 </plugin>
152
153 </model>
154
155 <model name="sphere">
156 <pose>0 1.5 0.5 0 0 0</pose>
157 <link name="sphere_link">
158 <inertial>
159 <inertia>
160 <ixx>0.1</ixx>
161 <ixy>0</ixy>
162 <ixz>0</ixz>
163 <iyy>0.1</iyy>
164 <iyz>0</iyz>
165 <izz>0.1</izz>
166 </inertia>
167 <mass>1.0</mass>
168 </inertial>
169 <collision name="sphere_collision">
170 <geometry>
171 <sphere>
172 <radius>0.5</radius>
173 </sphere>
174 </geometry>
175 </collision>
176
177 <visual name="sphere_visual">
178 <geometry>
179 <sphere>
180 <radius>0.5</radius>
181 </sphere>
182 </geometry>
183 <material>
184 <ambient>0 0 1 1</ambient>
185 <diffuse>0 0 1 1</diffuse>
186 <specular>0 0 1 1</specular>
187 </material>
188 </visual>
189 </link>
190
191 <plugin
192 filename="gz-sim-pose-publisher-system"
193 name="gz::sim::systems::PosePublisher">
194 <publish_link_pose>false</publish_link_pose>
195 <publish_collision_pose>false</publish_collision_pose>
196 <publish_visual_pose>false</publish_visual_pose>
197 <publish_nested_model_pose>true</publish_nested_model_pose>
198 </plugin>
199
200 </model>
201
202 <model name="capsule">
203 <pose>0 -3.0 0.5 0 0 0</pose>
204 <link name="capsule_link">
205 <inertial>
206 <inertia>
207 <ixx>0.074154</ixx>
208 <ixy>0</ixy>
209 <ixz>0</ixz>
210 <iyy>0.074154</iyy>
211 <iyz>0</iyz>
212 <izz>0.018769</izz>
213 </inertia>
214 <mass>1.0</mass>
215 </inertial>
216 <collision name="capsule_collision">
217 <geometry>
218 <capsule>
219 <radius>0.2</radius>
220 <length>0.6</length>
221 </capsule>
222 </geometry>
223 </collision>
224 <visual name="capsule_visual">
225 <geometry>
226 <capsule>
227 <radius>0.2</radius>
228 <length>0.6</length>
229 </capsule>
230 </geometry>
231 <material>
232 <ambient>1 1 0 1</ambient>
233 <diffuse>1 1 0 1</diffuse>
234 <specular>1 1 0 1</specular>
235 </material>
236 </visual>
237 </link>
238
239 <plugin
240 filename="gz-sim-pose-publisher-system"
241 name="gz::sim::systems::PosePublisher">
242 <publish_link_pose>false</publish_link_pose>
243 <publish_collision_pose>false</publish_collision_pose>
244 <publish_visual_pose>false</publish_visual_pose>
245 <publish_nested_model_pose>true</publish_nested_model_pose>
246 </plugin>
247
248 </model>
249
250 <model name="ellipsoid">
251 <pose>0 3.0 0.5 0 0 0</pose>
252 <link name="ellipsoid_link">
253 <inertial>
254 <inertia>
255 <ixx>0.068</ixx>
256 <ixy>0</ixy>
257 <ixz>0</ixz>
258 <iyy>0.058</iyy>
259 <iyz>0</iyz>
260 <izz>0.026</izz>
261 </inertia>
262 <mass>1.0</mass>
263 </inertial>
264 <collision name="ellipsoid_collision">
265 <geometry>
266 <ellipsoid>
267 <radii>0.2 0.3 0.5</radii>
268 </ellipsoid>
269 </geometry>
270 </collision>
271 <visual name="ellipsoid_visual">
272 <geometry>
273 <ellipsoid>
274 <radii>0.2 0.3 0.5</radii>
275 </ellipsoid>
276 </geometry>
277 <material>
278 <ambient>1 0 1 1</ambient>
279 <diffuse>1 0 1 1</diffuse>
280 <specular>1 0 1 1</specular>
281 </material>
282 </visual>
283 </link>
284
285 <plugin
286 filename="gz-sim-pose-publisher-system"
287 name="gz::sim::systems::PosePublisher">
288 <publish_link_pose>false</publish_link_pose>
289 <publish_collision_pose>false</publish_collision_pose>
290 <publish_visual_pose>false</publish_visual_pose>
291 <publish_nested_model_pose>true</publish_nested_model_pose>
292 </plugin>
293
294 </model>
295
296 <model name="cone">
297 <pose>0 4.5 0.5 0 0 0</pose>
298 <link name="cone_link">
299 <inertial auto="true">
300 <density>1</density>
301 </inertial>
302 <collision name="cone_collision">
303 <geometry>
304 <cone>
305 <radius>0.5</radius>
306 <length>1.0</length>
307 </cone>
308 </geometry>
309 </collision>
310
311 <visual name="cone_visual">
312 <geometry>
313 <cone>
314 <radius>0.5</radius>
315 <length>1.0</length>
316 </cone>
317 </geometry>
318 <material>
319 <ambient>1 0.47 0 1</ambient>
320 <diffuse>1 0.47 0 1</diffuse>
321 <specular>1 0.47 0 1</specular>
322 </material>
323 </visual>
324 </link>
325
326 <plugin
327 filename="gz-sim-pose-publisher-system"
328 name="gz::sim::systems::PosePublisher">
329 <publish_link_pose>false</publish_link_pose>
330 <publish_collision_pose>false</publish_collision_pose>
331 <publish_visual_pose>false</publish_visual_pose>
332 <publish_nested_model_pose>true</publish_nested_model_pose>
333 </plugin>
334
335 </model>
336 </world>
337</sdf>
We open Gazebo with this scene, as follows, then run the simulation by clicking the run button.
gz sim ~/gazebo_tutorial_workspace/scenes/shapes_with_pose_publisher.sdf
Note
Don’t forget to run the simulation otherwise most information will not be available.
The plugin for each entity will create a pose topic. We can verify that with the following command.
gz topic -l
The result will be as follows, where the relevant topics are highlighted.
/clock
/gazebo/resource_paths
/gui/camera/pose
/gui/currently_tracked
/gui/track
/model/box/pose
/model/capsule/pose
/model/cone/pose
/model/cylinder/pose
/model/ellipsoid/pose
/model/sphere/pose
/stats
/world/shapes_with_pose_publisher/clock
/world/shapes_with_pose_publisher/dynamic_pose/info
/world/shapes_with_pose_publisher/pose/info
/world/shapes_with_pose_publisher/scene/deletion
/world/shapes_with_pose_publisher/scene/info
/world/shapes_with_pose_publisher/state
/world/shapes_with_pose_publisher/stats
/world/shapes_with_pose_publisher/light_config
/world/shapes_with_pose_publisher/material_color
As always, we can investigate the Gazebo type these topics, as we expect all of them to be the same as they come from the same plugin. Let’s choose the box as it’s the first entity on the list.
We use the following command.
gz topic -i --topic /model/box/pose
It will output the type.
Publishers [Address, Message Type]:
tcp://172.16.191.128:41611, gz.msgs.Pose
No subscribers on topic [/model/box/pose]
Because this will be an unilateral bridge from Gazebo to ROS2, we use the [ instead of @
as follows.
ros2 run ros_gz_bridge \
parameter_bridge \
/model/box/pose@geometry_msgs/msg/Pose[gz.msgs.Pose
We can see the contents of the topic with the following command. It will show the real-time information of the entity, even if you move it around within Gazebo.
ros2 topic echo /model/box/pose
We can see how fast your bridge is running with the usual command below.
ros2 topic hz /model/box/pose
Depending on the quality of your machine, your results will very, but you should expect this frequency to be quite high.
average rate: 799.066
min: 0.000s max: 0.009s std dev: 0.00142s window: 800
average rate: 824.706
min: 0.000s max: 0.009s std dev: 0.00129s window: 1652
average rate: 811.552
min: 0.000s max: 0.010s std dev: 0.00131s window: 2439
average rate: 815.633
min: 0.000s max: 0.010s std dev: 0.00129s window: 3267
Exercises
I have shown how to obtain the pose of the box entity. This scene has other five topics, namely.
/model/capsule/pose
/model/cone/pose
/model/cylinder/pose
/model/ellipsoid/pose
/model/sphere/pose
Can you run the bridge of each one of these and see the results of each of these entities?
Getting transforms#
Warning
You’ll notice that each scene creates a Gazebo topic called /world/<SCENE>/pose/info where
<SCENE> is the name of the active scene. Although this publishes useful information when checking through
Gazebo topics, it does not play well with ros_gz_bridge. You can get the transform information
without the headers, which in ROS2 is not useful.
See also
Integration with other parts of ROS2 is important, therefore it could be useful to have all poses of relevant
objects available for tf2. In this case, we need to modify the message that is published by Gazebo, but
otherwise there is no big difference.
Our use of gz::sim::systems::PosePublisher will be slightly modified to have <use_pose_vector_msg>true</use_pose_vector_msg>,
highlighted below.
<plugin
filename="gz-sim-pose-publisher-system"
name="gz::sim::systems::PosePublisher">
<use_pose_vector_msg>true</use_pose_vector_msg>
<publish_link_pose>false</publish_link_pose>
<publish_collision_pose>false</publish_collision_pose>
<publish_visual_pose>false</publish_visual_pose>
<publish_nested_model_pose>true</publish_nested_model_pose>
</plugin>
Add the following file to your ~/gazebo_tutorial_workspace/scenes folder.
Contents of shapes_with_tf2_publisher.sdf
This is shapes_with_pose_publisher.sdf with one additional line in each gz::sim::systems::PosePublisher
plugin.
1<?xml version="1.0" ?>
2<sdf version="1.11">
3 <!--
4 Try moving a model using the command in the following CDATA block::
5 -->
6 <![CDATA[
7 gz service -s /world/shapes/set_pose \
8 --reqtype gz.msgs.Pose --reptype gz.msgs.Boolean \
9 --timeout 300 --req 'name: "box", position: {z: 5.0}'
10 ]]>
11 <world name="shapes_with_tf2_publisher">
12
13 <scene>
14 <ambient>1.0 1.0 1.0</ambient>
15 <background>0.8 0.8 0.8</background>
16 </scene>
17
18 <light type="directional" name="sun">
19 <cast_shadows>true</cast_shadows>
20 <pose>0 0 10 0 0 0</pose>
21 <diffuse>0.8 0.8 0.8 1</diffuse>
22 <specular>0.2 0.2 0.2 1</specular>
23 <attenuation>
24 <range>1000</range>
25 <constant>0.9</constant>
26 <linear>0.01</linear>
27 <quadratic>0.001</quadratic>
28 </attenuation>
29 <direction>-0.5 0.1 -0.9</direction>
30 </light>
31
32 <model name="ground_plane">
33 <static>true</static>
34 <link name="link">
35 <collision name="collision">
36 <geometry>
37 <plane>
38 <normal>0 0 1</normal>
39 <size>100 100</size>
40 </plane>
41 </geometry>
42 </collision>
43 <visual name="visual">
44 <geometry>
45 <plane>
46 <normal>0 0 1</normal>
47 <size>100 100</size>
48 </plane>
49 </geometry>
50 <material>
51 <ambient>0.8 0.8 0.8 1</ambient>
52 <diffuse>0.8 0.8 0.8 1</diffuse>
53 <specular>0.8 0.8 0.8 1</specular>
54 </material>
55 </visual>
56 </link>
57 </model>
58
59 <model name="box">
60 <pose>0 0 0.5 0 0 0</pose>
61 <link name="box_link">
62 <inertial>
63 <inertia>
64 <ixx>0.16666</ixx>
65 <ixy>0</ixy>
66 <ixz>0</ixz>
67 <iyy>0.16666</iyy>
68 <iyz>0</iyz>
69 <izz>0.16666</izz>
70 </inertia>
71 <mass>1.0</mass>
72 </inertial>
73 <collision name="box_collision">
74 <geometry>
75 <box>
76 <size>1 1 1</size>
77 </box>
78 </geometry>
79 </collision>
80
81 <visual name="box_visual">
82 <geometry>
83 <box>
84 <size>1 1 1</size>
85 </box>
86 </geometry>
87 <material>
88 <ambient>1 0 0 1</ambient>
89 <diffuse>1 0 0 1</diffuse>
90 <specular>1 0 0 1</specular>
91 </material>
92 </visual>
93 </link>
94
95 <plugin
96 filename="gz-sim-pose-publisher-system"
97 name="gz::sim::systems::PosePublisher">
98 <use_pose_vector_msg>true</use_pose_vector_msg>
99 <publish_link_pose>false</publish_link_pose>
100 <publish_collision_pose>false</publish_collision_pose>
101 <publish_visual_pose>false</publish_visual_pose>
102 <publish_nested_model_pose>true</publish_nested_model_pose>
103 </plugin>
104
105 </model>
106
107 <model name="cylinder">
108 <pose>0 -1.5 0.5 0 0 0</pose>
109 <link name="cylinder_link">
110 <inertial>
111 <inertia>
112 <ixx>0.1458</ixx>
113 <ixy>0</ixy>
114 <ixz>0</ixz>
115 <iyy>0.1458</iyy>
116 <iyz>0</iyz>
117 <izz>0.125</izz>
118 </inertia>
119 <mass>1.0</mass>
120 </inertial>
121 <collision name="cylinder_collision">
122 <geometry>
123 <cylinder>
124 <radius>0.5</radius>
125 <length>1.0</length>
126 </cylinder>
127 </geometry>
128 </collision>
129
130 <visual name="cylinder_visual">
131 <geometry>
132 <cylinder>
133 <radius>0.5</radius>
134 <length>1.0</length>
135 </cylinder>
136 </geometry>
137 <material>
138 <ambient>0 1 0 1</ambient>
139 <diffuse>0 1 0 1</diffuse>
140 <specular>0 1 0 1</specular>
141 </material>
142 </visual>
143 </link>
144
145 <plugin
146 filename="gz-sim-pose-publisher-system"
147 name="gz::sim::systems::PosePublisher">
148 <use_pose_vector_msg>true</use_pose_vector_msg>
149 <publish_link_pose>false</publish_link_pose>
150 <publish_collision_pose>false</publish_collision_pose>
151 <publish_visual_pose>false</publish_visual_pose>
152 <publish_nested_model_pose>true</publish_nested_model_pose>
153 </plugin>
154
155 </model>
156
157 <model name="sphere">
158 <pose>0 1.5 0.5 0 0 0</pose>
159 <link name="sphere_link">
160 <inertial>
161 <inertia>
162 <ixx>0.1</ixx>
163 <ixy>0</ixy>
164 <ixz>0</ixz>
165 <iyy>0.1</iyy>
166 <iyz>0</iyz>
167 <izz>0.1</izz>
168 </inertia>
169 <mass>1.0</mass>
170 </inertial>
171 <collision name="sphere_collision">
172 <geometry>
173 <sphere>
174 <radius>0.5</radius>
175 </sphere>
176 </geometry>
177 </collision>
178
179 <visual name="sphere_visual">
180 <geometry>
181 <sphere>
182 <radius>0.5</radius>
183 </sphere>
184 </geometry>
185 <material>
186 <ambient>0 0 1 1</ambient>
187 <diffuse>0 0 1 1</diffuse>
188 <specular>0 0 1 1</specular>
189 </material>
190 </visual>
191 </link>
192
193 <plugin
194 filename="gz-sim-pose-publisher-system"
195 name="gz::sim::systems::PosePublisher">
196 <use_pose_vector_msg>true</use_pose_vector_msg>
197 <publish_link_pose>false</publish_link_pose>
198 <publish_collision_pose>false</publish_collision_pose>
199 <publish_visual_pose>false</publish_visual_pose>
200 <publish_nested_model_pose>true</publish_nested_model_pose>
201 </plugin>
202
203 </model>
204
205 <model name="capsule">
206 <pose>0 -3.0 0.5 0 0 0</pose>
207 <link name="capsule_link">
208 <inertial>
209 <inertia>
210 <ixx>0.074154</ixx>
211 <ixy>0</ixy>
212 <ixz>0</ixz>
213 <iyy>0.074154</iyy>
214 <iyz>0</iyz>
215 <izz>0.018769</izz>
216 </inertia>
217 <mass>1.0</mass>
218 </inertial>
219 <collision name="capsule_collision">
220 <geometry>
221 <capsule>
222 <radius>0.2</radius>
223 <length>0.6</length>
224 </capsule>
225 </geometry>
226 </collision>
227 <visual name="capsule_visual">
228 <geometry>
229 <capsule>
230 <radius>0.2</radius>
231 <length>0.6</length>
232 </capsule>
233 </geometry>
234 <material>
235 <ambient>1 1 0 1</ambient>
236 <diffuse>1 1 0 1</diffuse>
237 <specular>1 1 0 1</specular>
238 </material>
239 </visual>
240 </link>
241
242 <plugin
243 filename="gz-sim-pose-publisher-system"
244 name="gz::sim::systems::PosePublisher">
245 <use_pose_vector_msg>true</use_pose_vector_msg>
246 <publish_link_pose>false</publish_link_pose>
247 <publish_collision_pose>false</publish_collision_pose>
248 <publish_visual_pose>false</publish_visual_pose>
249 <publish_nested_model_pose>true</publish_nested_model_pose>
250 </plugin>
251
252 </model>
253
254 <model name="ellipsoid">
255 <pose>0 3.0 0.5 0 0 0</pose>
256 <link name="ellipsoid_link">
257 <inertial>
258 <inertia>
259 <ixx>0.068</ixx>
260 <ixy>0</ixy>
261 <ixz>0</ixz>
262 <iyy>0.058</iyy>
263 <iyz>0</iyz>
264 <izz>0.026</izz>
265 </inertia>
266 <mass>1.0</mass>
267 </inertial>
268 <collision name="ellipsoid_collision">
269 <geometry>
270 <ellipsoid>
271 <radii>0.2 0.3 0.5</radii>
272 </ellipsoid>
273 </geometry>
274 </collision>
275 <visual name="ellipsoid_visual">
276 <geometry>
277 <ellipsoid>
278 <radii>0.2 0.3 0.5</radii>
279 </ellipsoid>
280 </geometry>
281 <material>
282 <ambient>1 0 1 1</ambient>
283 <diffuse>1 0 1 1</diffuse>
284 <specular>1 0 1 1</specular>
285 </material>
286 </visual>
287 </link>
288
289 <plugin
290 filename="gz-sim-pose-publisher-system"
291 name="gz::sim::systems::PosePublisher">
292 <use_pose_vector_msg>true</use_pose_vector_msg>
293 <publish_link_pose>false</publish_link_pose>
294 <publish_collision_pose>false</publish_collision_pose>
295 <publish_visual_pose>false</publish_visual_pose>
296 <publish_nested_model_pose>true</publish_nested_model_pose>
297 </plugin>
298
299 </model>
300
301 <model name="cone">
302 <pose>0 4.5 0.5 0 0 0</pose>
303 <link name="cone_link">
304 <inertial auto="true">
305 <density>1</density>
306 </inertial>
307 <collision name="cone_collision">
308 <geometry>
309 <cone>
310 <radius>0.5</radius>
311 <length>1.0</length>
312 </cone>
313 </geometry>
314 </collision>
315
316 <visual name="cone_visual">
317 <geometry>
318 <cone>
319 <radius>0.5</radius>
320 <length>1.0</length>
321 </cone>
322 </geometry>
323 <material>
324 <ambient>1 0.47 0 1</ambient>
325 <diffuse>1 0.47 0 1</diffuse>
326 <specular>1 0.47 0 1</specular>
327 </material>
328 </visual>
329 </link>
330
331 <plugin
332 filename="gz-sim-pose-publisher-system"
333 name="gz::sim::systems::PosePublisher">
334 <use_pose_vector_msg>true</use_pose_vector_msg>
335 <publish_link_pose>false</publish_link_pose>
336 <publish_collision_pose>false</publish_collision_pose>
337 <publish_visual_pose>false</publish_visual_pose>
338 <publish_nested_model_pose>true</publish_nested_model_pose>
339 </plugin>
340
341 </model>
342 </world>
343</sdf>
We open Gazebo with this scene, as follows, then run the simulation by clicking the run button.
gz sim ~/gazebo_tutorial_workspace/scenes/shapes_with_tf2_publisher.sdf
Note
Don’t forget to run the simulation otherwise most information will not be available.
In another terminal, we can check the type of message being used to publish poses.
gz topic -i --topic /model/box/pose
The output will be similar to the one below. Our modification in the plugin makes the Gazebo topic use a different
message type, gz.msgs.Pose_V.
Publishers [Address, Message Type]:
tcp://172.16.191.128:34555, gz.msgs.Pose_V
Subscribers [Address, Message Type]:
tcp://172.16.191.128:37389, gz.msgs.Pose_V
The idea now is to bridge that type of message with tf2. Beyond simply bridging the topics, we have to make sure that
these two points are correct.
All transforms are published to a topic named
/tf, for compatibility withtf2.The clock used in ROS2 matches the one used in Gazebo. This will make sure that when we look up transforms the timestamp will make sense.
Now, because we have seven topics to bridge, it would not be practical to have that done through the command line. In addition we need topics that have different names in Gazebo and ROS2.
We can take advantage of .yaml configuration files that are supported by ros_gz_bridge.
To show how this works, let us create a folder for our .yaml bridge files.
mkdir -p ~/gazebo_tutorial_workspace/bridge_config
cd ~/gazebo_tutorial_workspace/bridge_config
We add the following file to the newly created folder. The /clock bridge and the /tf bridge elements that are new
are highlighted.
1- ros_topic_name: "/clock"
2 gz_topic_name: "/clock"
3 ros_type_name: "rosgraph_msgs/msg/Clock"
4 gz_type_name: "gz.msgs.Clock"
5 direction: GZ_TO_ROS
6
7- ros_topic_name: "/tf"
8 gz_topic_name: "/model/box/pose"
9 ros_type_name: "tf2_msgs/msg/TFMessage"
10 gz_type_name: "gz.msgs.Pose_V"
11 direction: GZ_TO_ROS
12
13- ros_topic_name: "/tf"
14 gz_topic_name: "/model/capsule/pose"
15 ros_type_name: "tf2_msgs/msg/TFMessage"
16 gz_type_name: "gz.msgs.Pose_V"
17 direction: GZ_TO_ROS
18
19- ros_topic_name: "/tf"
20 gz_topic_name: "/model/cone/pose"
21 ros_type_name: "tf2_msgs/msg/TFMessage"
22 gz_type_name: "gz.msgs.Pose_V"
23 direction: GZ_TO_ROS
24
25- ros_topic_name: "/tf"
26 gz_topic_name: "/model/cylinder/pose"
27 ros_type_name: "tf2_msgs/msg/TFMessage"
28 gz_type_name: "gz.msgs.Pose_V"
29 direction: GZ_TO_ROS
30
31- ros_topic_name: "/tf"
32 gz_topic_name: "/model/ellipsoid/pose"
33 ros_type_name: "tf2_msgs/msg/TFMessage"
34 gz_type_name: "gz.msgs.Pose_V"
35 direction: GZ_TO_ROS
36
37- ros_topic_name: "/tf"
38 gz_topic_name: "/model/sphere/pose"
39 ros_type_name: "tf2_msgs/msg/TFMessage"
40 gz_type_name: "gz.msgs.Pose_V"
41 direction: GZ_TO_ROS
Note
You will see that bridge files allow more flexibility. For instance, we are able to bridge topics in that have different names in Gazebo and ROS2.
We now have to call ros_gz_bridge using this newly created file. Note that some bash commands will
not expand ~ into the home folder. We can replace those instances safely with $HOME. We send any configuration we
want with the flag --ros-args -p, then set the parameter config_file to have a path to our newly created configuration
file.
ros2 run ros_gz_bridge \
parameter_bridge \
--ros-args -p \
config_file:=$HOME/gazebo_tutorial_workspace/bridge_config/transforms.yaml
In the messages published to tf2 by gazebo, you will notice that the frame of reference is the name of the scene.
In this case, shapes_with_tf2_publisher. Therefore, to see that the frames are correctly published via ROS2,
we can see them in rviz2 with the following command.
ros2 run rviz2 rviz2 -f shapes_with_tf2_publisher
After adding the TF display, you’ll be able to see all the relevant frames.
Exercise
Suppose that you added a new model to shapes_with_tf2_publisher.sdf and you wanted to publish that information
to /tf as well. What files would you modify and what steps would you take to make that possible?
So far, we have seen the basics of ros_gz_bridge, mostly allowing us to expose Gazebo information in ROS2. We haven’t used any of these in our own nodes, so we will do that in the following section.