Skip to content

Commit

Permalink
Add a namespaced example (#457)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich authored Dec 23, 2024
1 parent a2e6e76 commit a7d5a40
Show file tree
Hide file tree
Showing 5 changed files with 147 additions and 5 deletions.
14 changes: 13 additions & 1 deletion doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -185,7 +185,6 @@ SDF:

.. code-block:: xml
<plugin filename="libgz_ros2_control-system.so" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
...
<ros>
Expand Down Expand Up @@ -286,6 +285,7 @@ gz_ros2_control_demos

There are some examples in the *gz_ros2_control_demos* package.
To specify whether to use URDF or SDF, you can launch the demo in the following way (the default is URDF):

.. code-block:: shell
ros2 launch gz_ros2_control_demos <launch file> description_format:=sdf
Expand Down Expand Up @@ -336,6 +336,18 @@ When the Gazebo world is launched you can run some of the following commands to
ros2 run gz_ros2_control_demos example_tricycle_drive
ros2 run gz_ros2_control_demos example_ackermann_drive
To demonstrate the setup of a namespaced robot, run

.. code-block:: shell
ros2 launch gz_ros2_control_demos diff_drive_example_namespaced.launch.py
which will launch a diff drive robot within the namespace ``r1``.

.. note::

The ros2_control settings for the controller_manager and the controller defined in ``diff_drive_controller.yaml`` use wildcards to match all namespaces.

To run the Mecanum mobile robot run the following commands to drive it from the keyboard:

.. code-block:: shell
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
controller_manager:
/**/controller_manager:
ros__parameters:
update_rate: 100 # Hz

joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

diff_drive_base_controller:
/**/diff_drive_base_controller:
ros__parameters:
type: diff_drive_controller/DiffDriveController
left_wheel_names: ["left_wheel_joint"]
Expand Down
2 changes: 1 addition & 1 deletion gz_ros2_control_demos/launch/diff_drive_example.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ def robot_state_publisher(context):
[
FindPackageShare('gz_ros2_control_demos'),
'config',
'diff_drive_controller_velocity.yaml',
'diff_drive_controller.yaml',
]
)

Expand Down
124 changes: 124 additions & 0 deletions gz_ros2_control_demos/launch/diff_drive_example_namespaced.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,124 @@
# Copyright 2024 Open Source Robotics Foundation, Inc.
#
# Licensed under the Apache License, Version 2.0 (the "License");
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# http://www.apache.org/licenses/LICENSE-2.0
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an "AS IS" BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.actions import RegisterEventHandler
from launch.event_handlers import OnProcessExit
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution

from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare


def generate_launch_description():
# Launch Arguments
use_sim_time = LaunchConfiguration('use_sim_time', default=True)

# Get URDF via xacro
robot_description_content = Command(
[
PathJoinSubstitution([FindExecutable(name='xacro')]),
' ',
PathJoinSubstitution(
[FindPackageShare('gz_ros2_control_demos'),
'urdf', 'test_diff_drive.xacro.urdf']
),
' ',
'namespace:=r1',
]
)
robot_description = {'robot_description': robot_description_content}
robot_controllers = PathJoinSubstitution(
[
FindPackageShare('gz_ros2_control_demos'),
'config',
'diff_drive_controller.yaml',
]
)

node_robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
namespace='r1',
output='screen',
parameters=[robot_description]
)

gz_spawn_entity = Node(
package='ros_gz_sim',
executable='create',
namespace='r1',
output='screen',
arguments=['-topic', 'robot_description', '-name',
'diff_drive', '-allow_renaming', 'true'],
)

joint_state_broadcaster_spawner = Node(
package='controller_manager',
executable='spawner',
arguments=[
'joint_state_broadcaster',
'-c', '/r1/controller_manager'
],
)
diff_drive_base_controller_spawner = Node(
package='controller_manager',
executable='spawner',
arguments=[
'diff_drive_base_controller',
'--param-file',
robot_controllers,
'-c', '/r1/controller_manager'
],
)

# Bridge
bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=['/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock'],
output='screen'
)

return LaunchDescription([
# Launch gazebo environment
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[PathJoinSubstitution([FindPackageShare('ros_gz_sim'),
'launch',
'gz_sim.launch.py'])]),
launch_arguments=[('gz_args', [' -r -v 4 empty.sdf'])]),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gz_spawn_entity,
on_exit=[joint_state_broadcaster_spawner],
)
),
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=joint_state_broadcaster_spawner,
on_exit=[diff_drive_base_controller_spawner],
)
),
bridge,
node_robot_state_publisher,
gz_spawn_entity,
# Launch Arguments
DeclareLaunchArgument(
'use_sim_time',
default_value=use_sim_time,
description='If true, use simulated clock'),
])
8 changes: 7 additions & 1 deletion gz_ros2_control_demos/urdf/test_diff_drive.xacro.urdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,8 @@
<?xml version="1.0"?>
<robot name="diff_drive" xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:arg name="namespace" default="" />

<material name="orange">
<color rgba="0.8 0.4 0.0 1.0"/>
</material>
Expand Down Expand Up @@ -168,7 +171,10 @@
<gazebo>
<!-- Joint state publisher -->
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
<parameters>$(find gz_ros2_control_demos)/config/diff_drive_controller_velocity.yaml</parameters>
<ros>
<namespace>$(arg namespace)</namespace>
</ros>
<parameters>$(find gz_ros2_control_demos)/config/diff_drive_controller.yaml</parameters>
</plugin>
</gazebo>

Expand Down

0 comments on commit a7d5a40

Please sign in to comment.