@@ -86,7 +86,7 @@ Now we start the ROS listener.
86
86
87
87
```
88
88
# Shell B:
89
- . /opt/ros/galactic /setup.bash
89
+ . /opt/ros/humble /setup.bash
90
90
ros2 topic echo /chatter
91
91
```
92
92
@@ -118,7 +118,7 @@ Now we start the ROS talker.
118
118
119
119
```
120
120
# Shell C:
121
- . /opt/ros/galactic /setup.bash
121
+ . /opt/ros/humble /setup.bash
122
122
ros2 topic pub /chatter std_msgs/msg/String "data: 'Hi'" --once
123
123
```
124
124
@@ -156,15 +156,15 @@ Now we start the ROS GUI:
156
156
157
157
```
158
158
# Shell C:
159
- . /opt/ros/galactic /setup.bash
159
+ . /opt/ros/humble /setup.bash
160
160
ros2 run rqt_image_view rqt_image_view /rgbd_camera/image
161
161
```
162
162
163
163
You should see the current images in ` rqt_image_view ` which are coming from
164
164
Gazebo (published as Gazebo Msgs over Gazebo Transport).
165
165
166
166
The screenshot shows all the shell windows and their expected content
167
- (it was taken using ROS 2 Galactic and Gazebo Fortress):
167
+ (it was taken using ROS 2 humble and Gazebo Fortress):
168
168
169
169
![ Gazebo Transport images and ROS rqt] ( images/bridge_image_exchange.png )
170
170
@@ -274,9 +274,44 @@ To run the bridge node with the above configuration:
274
274
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=$WORKSPACE /ros_gz/ros_gz_bridge/test/config/full.yaml
275
275
```
276
276
277
+ ## Example 6: Using ROS namespace with the Bridge
278
+
279
+ When spawning multiple robots inside the same ROS environment, it is convenient to use namespaces to avoid overlapping topic names.
280
+ There are three main types of namespaces: relative, global (` / ` ) and private (` ~/ ` ). For more information, refer to ROS documentation.
281
+ Namespaces are applied to Gazebo topic both when specified as ` topic_name ` as well as ` gz_topic_name ` .
282
+
283
+ By default, the Bridge will not apply ROS namespace on the Gazebo topics. To enable this feature, use parameter ` expand_gz_topic_names ` .
284
+ Let's test our topic with namespace:
285
+
286
+ ```
287
+ # Shell A:
288
+ . ~/bridge_ws/install/setup.bash
289
+ ros2 run ros_gz_bridge parameter_bridge chatter@std_msgs/msg/String@ignition.msgs.StringMsg \
290
+ --ros-args -p expand_gz_topic_names:=true -r __ns:=/demo
291
+ ```
292
+
293
+ Now we start the Gazebo Transport listener.
294
+
295
+ ```
296
+ # Shell B:
297
+ ign topic -e -t /demo/chatter
298
+ ```
299
+
300
+ Now we start the ROS talker.
301
+
302
+ ```
303
+ # Shell C:
304
+ . /opt/ros/humble/setup.bash
305
+ ros2 topic pub /demo/chatter std_msgs/msg/String "data: 'Hi from inside of a namespace'" --once
306
+ ```
307
+
308
+ By changing ` chatter ` to ` /chatter ` or ` ~/chatter ` you can obtain different results.
309
+
310
+
277
311
## API
278
312
279
313
ROS 2 Parameters:
280
314
281
315
* ` subscription_heartbeat ` - Period at which the node checks for new subscribers for lazy bridges.
282
316
* ` config_file ` - YAML file to be loaded as the bridge configuration
317
+ * ` expand_gz_topic_names ` - Enable or disable ROS namespace applied on GZ topics.
0 commit comments