Skip to content
This repository was archived by the owner on May 18, 2025. It is now read-only.

Commit 01be3f3

Browse files
mergify[bot]bobbleballsahcorde
authored
Fix namespacing for multiple instances of gazebo_ros2_control plugin (#181) (#398)
Co-authored-by: ben.holden <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]> (cherry picked from commit 828b5f2) Co-authored-by: Ben Holden <[email protected]> Co-authored-by: Alejandro Hernández Cordero <[email protected]>
1 parent a28f4c6 commit 01be3f3

File tree

6 files changed

+491
-14
lines changed

6 files changed

+491
-14
lines changed

doc/index.rst

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -313,6 +313,54 @@ The following is a basic configuration of the controllers:
313313
.. literalinclude:: ../gazebo_ros2_control_demos/config/cart_controller.yaml
314314
:language: yaml
315315

316+
317+
Multiple Namespaces
318+
-----------------------------------------------------------
319+
The gazebo_ros2_control plugin can be launched in multiple namespaces. This is useful if it is desired to have multiple robots of the same description running at the same time.
320+
It is possible to directly define the namespace in the URDF file, as shown below:
321+
322+
.. code-block:: xml
323+
324+
<gazebo>
325+
<plugin name="gazebo_ros2_control" filename="libgazebo_ros2_control.so">
326+
<parameters> $(arg control_yaml) </parameters>
327+
<ros>
328+
<namespace>r1</namespace>
329+
<remapping>/tf:=tf</remapping>
330+
<remapping>/tf_static:=tf_static</remapping>
331+
<remapping>diffdrive_controller/odom:=odom</remapping>
332+
</ros>
333+
</plugin>
334+
</gazebo>
335+
336+
Where ``r1`` is the namespace associated to the particular instance of the plugin. Please note that the remapping of ``/tf`` and ``/tf_static`` is recommended only if you want to have a separate TF buffer for each namespace, e.g ``/r1/tf``
337+
338+
As an example, run the following command to launch the diff_drive example within the namespace ``r1``
339+
340+
.. code-block:: bash
341+
342+
ros2 launch gazebo_ros2_control_demos diff_drive_namespaced.launch.py
343+
344+
A second method to launch an instance with a particular namespace is by using the Gazebo ``spawn_entity.py`` tool and setting the ``-robot_namespace`` parameter to the script:
345+
346+
.. code-block:: bash
347+
348+
ros2 run gazebo_ros spawn_entity.py -entity robot_1 -robot_namespace r1 -topic robot_description
349+
350+
The script calls the ``spawn_entity`` service to spawn an entity named ``robot_1`` in the namespace ``r1``. It is assumed that a robot description is being published by a ``robot_state_publisher`` node on the topic ``robot_description``, this will also be used for the ``gazebo_ros2_control`` plugin.
351+
352+
The ``spawn_entity.py`` script will rewrite the robot description to include a namespace for every plugin tag. Please note that this method will apply a namespace to every plugin in the robot description. It will also overwrite any existing namespaces set in the description file.
353+
354+
As an example, run the following command to spawn two diff_drive robots in the namespaces ``r1`` and ``r2``
355+
356+
.. note::
357+
358+
The ros2_control settings for the controller_manager and the controller defined in ``diff_drive_controller_namespaced.yaml`` use wildcards to match both namespaces.
359+
360+
.. code-block:: bash
361+
362+
ros2 launch gazebo_ros2_control_demos diff_drive_pair_namespaced.launch.py
363+
316364
gazebo_ros2_control_demos
317365
==========================================
318366

gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp

Lines changed: 0 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -226,24 +226,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
226226

227227
if (sdf->HasElement("ros")) {
228228
sdf = sdf->GetElement("ros");
229-
230-
// Set namespace if tag is present
231-
if (sdf->HasElement("namespace")) {
232-
std::string ns = sdf->GetElement("namespace")->Get<std::string>();
233-
// prevent exception: namespace must be absolute, it must lead with a '/'
234-
if (ns.empty() || ns[0] != '/') {
235-
ns = '/' + ns;
236-
}
237-
std::string ns_arg = std::string("__ns:=") + ns;
238-
arguments.push_back(RCL_REMAP_FLAG);
239-
arguments.push_back(ns_arg);
240-
}
241-
242229
// Get list of remapping rules from SDF
243230
if (sdf->HasElement("remapping")) {
244231
sdf::ElementPtr argument_sdf = sdf->GetElement("remapping");
245232

246-
arguments.push_back(RCL_ROS_ARGS_FLAG);
247233
while (argument_sdf) {
248234
std::string argument = argument_sdf->Get<std::string>();
249235
arguments.push_back(RCL_REMAP_FLAG);
Lines changed: 50 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,50 @@
1+
/**/controller_manager:
2+
ros__parameters:
3+
update_rate: 100 # Hz
4+
use_sim_time: true
5+
6+
joint_state_broadcaster:
7+
type: joint_state_broadcaster/JointStateBroadcaster
8+
9+
diff_drive_base_controller:
10+
type: diff_drive_controller/DiffDriveController
11+
12+
/**/diff_drive_base_controller:
13+
ros__parameters:
14+
left_wheel_names: ["left_wheel_joint"]
15+
right_wheel_names: ["right_wheel_joint"]
16+
17+
wheel_separation: 1.25
18+
wheel_radius: 0.3
19+
20+
wheel_separation_multiplier: 1.0
21+
left_wheel_radius_multiplier: 1.0
22+
right_wheel_radius_multiplier: 1.0
23+
24+
publish_rate: 50.0
25+
odom_frame_id: odom
26+
base_frame_id: chassis
27+
pose_covariance_diagonal : [0.001, 0.001, 0.0, 0.0, 0.0, 0.01]
28+
twist_covariance_diagonal: [0.001, 0.0, 0.0, 0.0, 0.0, 0.01]
29+
30+
open_loop: true
31+
enable_odom_tf: true
32+
33+
cmd_vel_timeout: 0.5
34+
#publish_limited_velocity: true
35+
#velocity_rolling_window_size: 10
36+
37+
# Velocity and acceleration limits
38+
# Whenever a min_* is unspecified, default to -max_*
39+
linear.x.max_velocity: 1.0
40+
linear.x.min_velocity: -1.0
41+
linear.x.max_acceleration: 1.0
42+
linear.x.max_jerk: 0.0
43+
linear.x.min_jerk: 0.0
44+
45+
angular.z.max_velocity: 1.0
46+
angular.z.min_velocity: -1.0
47+
angular.z.max_acceleration: 1.0
48+
angular.z.min_acceleration: -1.0
49+
angular.z.max_jerk: 0.0
50+
angular.z.min_jerk: 0.0
Lines changed: 91 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,91 @@
1+
# Copyright 2024 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import os
16+
17+
from ament_index_python.packages import get_package_share_directory
18+
19+
20+
from launch import LaunchDescription
21+
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
22+
from launch.event_handlers import OnProcessExit
23+
from launch.launch_description_sources import PythonLaunchDescriptionSource
24+
25+
from launch_ros.actions import Node
26+
27+
import xacro
28+
29+
30+
def generate_launch_description():
31+
gazebo = IncludeLaunchDescription(
32+
PythonLaunchDescriptionSource([os.path.join(
33+
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
34+
)
35+
36+
gazebo_ros2_control_demos_path = os.path.join(
37+
get_package_share_directory('gazebo_ros2_control_demos'))
38+
39+
xacro_file = os.path.join(gazebo_ros2_control_demos_path,
40+
'urdf',
41+
'test_diff_drive_namespaced.xacro.urdf')
42+
43+
doc = xacro.parse(open(xacro_file))
44+
xacro.process_doc(doc)
45+
params = {'robot_description': doc.toxml()}
46+
47+
node_robot_state_publisher = Node(
48+
package='robot_state_publisher',
49+
executable='robot_state_publisher',
50+
namespace='r1',
51+
output='screen',
52+
parameters=[params]
53+
)
54+
55+
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
56+
namespace='r1',
57+
arguments=['-topic', 'robot_description',
58+
'-entity', 'diffbot'],
59+
output='screen')
60+
61+
load_joint_state_broadcaster = ExecuteProcess(
62+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
63+
'joint_state_broadcaster',
64+
'-c', '/r1/controller_manager'],
65+
output='screen'
66+
)
67+
68+
load_diff_drive_base_controller = ExecuteProcess(
69+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
70+
'diff_drive_base_controller',
71+
'-c', '/r1/controller_manager'],
72+
output='screen'
73+
)
74+
75+
return LaunchDescription([
76+
RegisterEventHandler(
77+
event_handler=OnProcessExit(
78+
target_action=spawn_entity,
79+
on_exit=[load_joint_state_broadcaster],
80+
)
81+
),
82+
RegisterEventHandler(
83+
event_handler=OnProcessExit(
84+
target_action=load_joint_state_broadcaster,
85+
on_exit=[load_diff_drive_base_controller],
86+
)
87+
),
88+
gazebo,
89+
node_robot_state_publisher,
90+
spawn_entity,
91+
])
Lines changed: 135 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,135 @@
1+
# Copyright 2024 Open Source Robotics Foundation, Inc.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import os
16+
17+
from ament_index_python.packages import get_package_share_directory
18+
19+
20+
from launch import LaunchDescription
21+
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
22+
from launch.event_handlers import OnProcessExit
23+
from launch.launch_description_sources import PythonLaunchDescriptionSource
24+
25+
from launch_ros.actions import Node
26+
27+
import xacro
28+
29+
30+
def generate_launch_description():
31+
gazebo = IncludeLaunchDescription(
32+
PythonLaunchDescriptionSource([os.path.join(
33+
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
34+
)
35+
36+
gazebo_ros2_control_demos_path = os.path.join(
37+
get_package_share_directory('gazebo_ros2_control_demos'))
38+
39+
xacro_file = os.path.join(gazebo_ros2_control_demos_path,
40+
'urdf',
41+
'test_diff_drive_namespaced.xacro.urdf')
42+
43+
doc = xacro.parse(open(xacro_file))
44+
xacro.process_doc(doc)
45+
params = {'robot_description': doc.toxml()}
46+
47+
node_robot_state_publisher_r1 = Node(
48+
package='robot_state_publisher',
49+
executable='robot_state_publisher',
50+
namespace='r1',
51+
output='screen',
52+
parameters=[params]
53+
)
54+
55+
node_robot_state_publisher_r2 = Node(
56+
package='robot_state_publisher',
57+
executable='robot_state_publisher',
58+
namespace='r2',
59+
output='screen',
60+
parameters=[params]
61+
)
62+
63+
spawn_entity_r1 = Node(
64+
package='gazebo_ros', executable='spawn_entity.py',
65+
arguments=[
66+
'-topic', '/r1/robot_description',
67+
'-robot_namespace', 'r1',
68+
'-entity', 'diffbot1'
69+
],
70+
output='screen'
71+
)
72+
73+
spawn_entity_r2 = Node(
74+
package='gazebo_ros', executable='spawn_entity.py',
75+
arguments=[
76+
'-topic', '/r2/robot_description',
77+
'-robot_namespace', 'r2',
78+
'-entity', 'diffbot1'
79+
],
80+
output='screen'
81+
)
82+
83+
load_joint_state_broadcaster_r1 = ExecuteProcess(
84+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
85+
'joint_state_broadcaster',
86+
'-c', '/r1/controller_manager'],
87+
output='screen'
88+
)
89+
90+
load_diff_drive_base_controller_r1 = ExecuteProcess(
91+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
92+
'diff_drive_base_controller',
93+
'-c', '/r1/controller_manager'],
94+
output='screen'
95+
)
96+
97+
load_joint_state_broadcaster_r2 = ExecuteProcess(
98+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
99+
'joint_state_broadcaster',
100+
'-c', '/r2/controller_manager'],
101+
output='screen'
102+
)
103+
104+
load_diff_drive_base_controller_r2 = ExecuteProcess(
105+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
106+
'diff_drive_base_controller',
107+
'-c', '/r2/controller_manager'],
108+
output='screen'
109+
)
110+
111+
return LaunchDescription([
112+
RegisterEventHandler(
113+
event_handler=OnProcessExit(
114+
target_action=spawn_entity_r1,
115+
on_exit=[
116+
load_joint_state_broadcaster_r1,
117+
load_diff_drive_base_controller_r1
118+
],
119+
)
120+
),
121+
RegisterEventHandler(
122+
event_handler=OnProcessExit(
123+
target_action=spawn_entity_r2,
124+
on_exit=[
125+
load_joint_state_broadcaster_r2,
126+
load_diff_drive_base_controller_r2
127+
],
128+
)
129+
),
130+
gazebo,
131+
node_robot_state_publisher_r1,
132+
node_robot_state_publisher_r2,
133+
spawn_entity_r1,
134+
spawn_entity_r2,
135+
])

0 commit comments

Comments
 (0)