Skip to content

Commit 017fbe6

Browse files
mergify[bot]christophfroehlichdestoglJuliaj
authored
[example_9] Switch to gz_ros2_control (backport #482) (#749)
* [example_9] Switch to gz_ros2_control (#482) * Switch from gazebo classic to gazebo * update docs * Use gz_ros2_control in semi-binary builds * rm dependency conditional Co-authored-by: Dr. Denis <[email protected]> * Remove gazebo classic from repos file * Add gazebo bridge node and fix some warnings (#755) (#757) (cherry picked from commit 2587970) Co-authored-by: Julia Jia <[email protected]> --------- Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Dr. Denis <[email protected]> Co-authored-by: Christoph Froehlich <[email protected]> Co-authored-by: mergify[bot] <37929162+mergify[bot]@users.noreply.github.com> Co-authored-by: Julia Jia <[email protected]>
1 parent 193d080 commit 017fbe6

14 files changed

+72
-85
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ The following examples are part of this demo repository:
5555

5656
*RRBot* with an exposed transmission interface.
5757

58-
* Example 9: ["Gazebo classic simulation"](example_9)
58+
* Example 9: ["Gazebo simulation"](example_9)
5959

6060
Demonstrates how to switch between simulation and hardware.
6161

doc/index.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -286,7 +286,7 @@ Examples
286286
Example 6: Modular robots with separate communication to each actuator <../example_6/doc/userdoc.rst>
287287
Example 7: Full tutorial with a 6DOF robot <../example_7/doc/userdoc.rst>
288288
Example 8: Using transmissions <../example_8/doc/userdoc.rst>
289-
Example 9: Gazebo classic <../example_9/doc/userdoc.rst>
289+
Example 9: Gazebo <../example_9/doc/userdoc.rst>
290290
Example 10: Industrial robot with GPIO interfaces <../example_10/doc/userdoc.rst>
291291
Example 11: CarlikeBot <../example_11/doc/userdoc.rst>
292292
Example 12: Controller chaining <../example_12/doc/userdoc.rst>

example_9/bringup/config/rrbot_controllers.yaml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
controller_manager:
22
ros__parameters:
3-
update_rate: 10 # Hz
3+
update_rate: 1000 # Hz
44

55
joint_state_broadcaster:
66
type: joint_state_broadcaster/JointStateBroadcaster

example_9/bringup/launch/rrbot_gazebo_classic.launch.py renamed to example_9/bringup/launch/rrbot_gazebo.launch.py

Lines changed: 28 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -36,11 +36,34 @@ def generate_launch_description():
3636
# Initialize Arguments
3737
gui = LaunchConfiguration("gui")
3838

39+
# gazebo
3940
gazebo = IncludeLaunchDescription(
4041
PythonLaunchDescriptionSource(
41-
[PathJoinSubstitution([FindPackageShare("gazebo_ros"), "launch", "gazebo.launch.py"])]
42+
[FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
4243
),
43-
launch_arguments={"verbose": "false"}.items(),
44+
launch_arguments={"gz_args": " -r -v 3 empty.sdf"}.items(),
45+
)
46+
47+
# Gazebo bridge
48+
gazebo_bridge = Node(
49+
package="ros_gz_bridge",
50+
executable="parameter_bridge",
51+
arguments=["/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock"],
52+
output="screen",
53+
)
54+
55+
gz_spawn_entity = Node(
56+
package="ros_gz_sim",
57+
executable="create",
58+
output="screen",
59+
arguments=[
60+
"-topic",
61+
"/robot_description",
62+
"-name",
63+
"rrbot_system_position",
64+
"-allow_renaming",
65+
"true",
66+
],
4467
)
4568

4669
# Get URDF via xacro
@@ -52,7 +75,7 @@ def generate_launch_description():
5275
[FindPackageShare("ros2_control_demo_example_9"), "urdf", "rrbot.urdf.xacro"]
5376
),
5477
" ",
55-
"use_gazebo_classic:=true",
78+
"use_gazebo:=true",
5679
]
5780
)
5881
robot_description = {"robot_description": robot_description_content}
@@ -67,13 +90,6 @@ def generate_launch_description():
6790
parameters=[robot_description],
6891
)
6992

70-
spawn_entity = Node(
71-
package="gazebo_ros",
72-
executable="spawn_entity.py",
73-
arguments=["-topic", "robot_description", "-entity", "rrbot_system_position"],
74-
output="screen",
75-
)
76-
7793
joint_state_broadcaster_spawner = Node(
7894
package="controller_manager",
7995
executable="spawner",
@@ -96,8 +112,9 @@ def generate_launch_description():
96112

97113
nodes = [
98114
gazebo,
115+
gazebo_bridge,
99116
node_robot_state_publisher,
100-
spawn_entity,
117+
gz_spawn_entity,
101118
joint_state_broadcaster_spawner,
102119
robot_controller_spawner,
103120
rviz_node,

example_9/description/gazebo/rrbot.gazebo.xacro

Lines changed: 19 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -9,28 +9,43 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
99

1010
<!-- ros_control plugin -->
1111
<gazebo>
12-
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
12+
<plugin filename="gz_ros2_control-system" name="gz_ros2_control::GazeboSimROS2ControlPlugin">
1313
<parameters>$(find ros2_control_demo_example_9)/config/rrbot_controllers.yaml</parameters>
1414
</plugin>
1515
</gazebo>
1616

1717
<!-- Link1 -->
1818
<gazebo reference="${prefix}base_link">
19-
<material>Gazebo/Orange</material>
19+
<material>
20+
<script>
21+
<uri>file://media/materials/scripts/gazebo.material</uri>
22+
<name>Gazebo/Orange</name>
23+
</script>
24+
</material>
2025
</gazebo>
2126

2227
<!-- Link2 -->
2328
<gazebo reference="${prefix}link1">
2429
<mu1>0.2</mu1>
2530
<mu2>0.2</mu2>
26-
<material>Gazebo/Yellow</material>
31+
<material>
32+
<script>
33+
<uri>file://media/materials/scripts/gazebo.material</uri>
34+
<name>Gazebo/Yellow</name>
35+
</script>
36+
</material>
2737
</gazebo>
2838

2939
<!-- Link3 -->
3040
<gazebo reference="${prefix}link2">
3141
<mu1>0.2</mu1>
3242
<mu2>0.2</mu2>
33-
<material>Gazebo/Orange</material>
43+
<material>
44+
<script>
45+
<uri>file://media/materials/scripts/gazebo.material</uri>
46+
<name>Gazebo/Yellow</name>
47+
</script>
48+
</material>
3449
</gazebo>
3550

3651
</xacro:macro>

example_9/description/ros2_control/rrbot.ros2_control.xacro

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
<?xml version="1.0"?>
22
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
33

4-
<xacro:macro name="rrbot_ros2_control" params="name prefix use_gazebo_classic:=^|false">
4+
<xacro:macro name="rrbot_ros2_control" params="name prefix use_gazebo:=^|false">
55

66
<ros2_control name="${name}" type="system">
77
<hardware>
8-
<xacro:if value="${use_gazebo_classic}">
9-
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
8+
<xacro:if value="${use_gazebo}">
9+
<plugin>gz_ros2_control/GazeboSimSystem</plugin>
1010
</xacro:if>
11-
<xacro:unless value="${use_gazebo_classic}">
11+
<xacro:unless value="${use_gazebo}">
1212
<plugin>ros2_control_demo_example_9/RRBotSystemPositionOnlyHardware</plugin>
1313
<param name="example_param_hw_start_duration_sec">0</param>
1414
<param name="example_param_hw_stop_duration_sec">3.0</param>

example_9/description/urdf/rrbot.urdf.xacro

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
66
-->
77
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="2dof_robot">
88
<xacro:arg name="prefix" default="" />
9-
<xacro:arg name="use_gazebo_classic" default="false" />
9+
<xacro:arg name="use_gazebo" default="false" />
1010

1111
<!-- Import RRBot macro -->
1212
<xacro:include filename="$(find ros2_control_demo_description)/rrbot/urdf/rrbot_description.urdf.xacro" />
@@ -25,9 +25,9 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
2525
</xacro:rrbot>
2626

2727
<xacro:rrbot_ros2_control
28-
name="RRBot" prefix="$(arg prefix)" use_gazebo_classic="$(arg use_gazebo_classic)"/>
28+
name="RRBot" prefix="$(arg prefix)" use_gazebo="$(arg use_gazebo)"/>
2929

30-
<xacro:if value="$(arg use_gazebo_classic)">
30+
<xacro:if value="$(arg use_gazebo)">
3131
<!-- Import Gazebo Classic definitions + plugin -->
3232
<xacro:include filename="$(find ros2_control_demo_example_9)/gazebo/rrbot.gazebo.xacro" />
3333
<xacro:rrbot_gazebo prefix="$(arg prefix)"/>

example_9/doc/rrbot_gazebo.png

79.1 KB
Loading
-22.2 KB
Binary file not shown.

example_9/doc/userdoc.rst

Lines changed: 10 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -6,34 +6,12 @@ Example 9: Simulation with RRBot
66
=================================
77

88
With *example_9*, we demonstrate the interaction of simulators with ros2_control. More specifically,
9-
Gazebo Classic is used for this purpose.
9+
gazebo is used for this purpose.
1010

1111
.. note::
1212

1313
Follow the installation instructions on :ref:`ros2_control_demos_install` how to install all dependencies,
14-
Gazebo Classic should be automatically installed.
15-
16-
* If you have installed and compiled this repository locally, you can directly use the commands below.
17-
* If you have installed it via the provided docker image: To run the first two steps of this example (without Gazebo Classic), use the commands as described with :ref:`ros2_control_demos_install`. To run the later steps using Gazebo Classic, execute
18-
19-
.. code::
20-
21-
docker run -it --rm --name ros2_control_demos --net host ros2_control_demos ros2 launch ros2_control_demo_example_9 rrbot_gazebo_classic.launch.py gui:=false
22-
23-
first. Then on your local machine you can run the Gazebo Classic client with
24-
25-
.. code-block:: shell
26-
27-
gzclient
28-
29-
and/or ``rviz2`` with
30-
31-
.. code-block:: shell
32-
33-
rviz2 -d src/ros2_control_demos/example_9/description/rviz/rrbot.rviz
34-
35-
36-
For details on the ``gazebo_ros2_control`` plugin, see :ref:`gazebo_ros2_control`.
14+
gazebo should be automatically installed. For details on the ``gz_ros2_control`` plugin, see :ref:`gz_ros2_control`.
3715

3816
Tutorial steps
3917
--------------------------
@@ -55,24 +33,18 @@ Tutorial steps
5533
5634
It uses an identical hardware interface as already discussed with *example_1*, see its docs on details on the hardware interface.
5735

58-
3. To start *RRBot* in the simulators, open a terminal, source your ROS2-workspace and Gazebo Classic installation first, i.e., by
59-
60-
.. code-block:: shell
61-
62-
source /usr/share/gazebo/setup.sh
63-
64-
Then, execute the launch file with
36+
3. To start *RRBot* in the simulators, open a terminal, source your ROS2-workspace first. Then, execute the launch file with
6537

6638
.. code-block:: shell
6739
68-
ros2 launch ros2_control_demo_example_9 rrbot_gazebo_classic.launch.py gui:=true
40+
ros2 launch ros2_control_demo_example_9 rrbot_gazebo.launch.py gui:=true
6941
70-
The launch file loads the robot description, starts Gazebo Classic, *Joint State Broadcaster* and *Forward Command Controller*.
71-
If you can see two orange and one yellow "box" in Gazebo Classic everything has started properly.
42+
The launch file loads the robot description, starts gazebo, *Joint State Broadcaster* and *Forward Command Controller*.
43+
If you can see two orange and one yellow "box" in gazebo everything has started properly.
7244

73-
.. image:: rrbot_gazebo_classic.png
45+
.. image:: rrbot_gazebo.png
7446
:width: 400
75-
:alt: Revolute-Revolute Manipulator Robot in Gazebo Classic
47+
:alt: Revolute-Revolute Manipulator Robot in gazebo
7648

7749
4. Check if the hardware interface loaded properly, by opening another terminal and executing
7850

@@ -118,7 +90,7 @@ Tutorial steps
11890
11991
ros2 launch ros2_control_demo_example_9 test_forward_position_controller.launch.py
12092
121-
You should now see the robot moving in Gazebo Classic.
93+
You should now see the robot moving in gazebo.
12294

12395
If you echo the ``/joint_states`` or ``/dynamic_joint_states`` topics you should see the changing values,
12496
namely the simulated states of the robot
@@ -135,7 +107,7 @@ Files used for this demos
135107
- Launch files:
136108

137109
+ Hardware: `rrbot.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_9/bringup/launch/rrbot.launch.py>`__
138-
+ Gazebo Classic: `rrbot_gazebo_classic.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_9/bringup/launch/rrbot_gazebo_classic.launch.py>`__
110+
+ gazebo: `rrbot_gazebo.launch.py <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_9/bringup/launch/rrbot_gazebo.launch.py>`__
139111

140112
- Controllers yaml: `rrbot_controllers.yaml <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_9/bringup/config/rrbot_controllers.yaml>`__
141113
- URDF file: `rrbot.urdf.xacro <https://github.com/ros-controls/ros2_control_demos/tree/{REPOS_FILE_BRANCH}/example_9/description/urdf/rrbot.urdf.xacro>`__

0 commit comments

Comments
 (0)