diff --git a/README.md b/README.md
index 572bf2828..62ce88a8e 100644
--- a/README.md
+++ b/README.md
@@ -52,7 +52,7 @@ The following examples are part of this demo repository:
*RRBot* with an exposed transmission interface.
-* Example 9: ["Gazebo classic simulation"](example_9)
+* Example 9: ["Gazebo simulation"](example_9)
Demonstrates how to switch between simulation and hardware.
diff --git a/doc/index.rst b/doc/index.rst
index 0837344a5..be15df819 100644
--- a/doc/index.rst
+++ b/doc/index.rst
@@ -269,7 +269,7 @@ Examples
Example 6: Modular robots with separate communication to each actuator <../example_6/doc/userdoc.rst>
Example 7: Full tutorial with a 6DOF robot <../example_7/doc/userdoc.rst>
Example 8: Using transmissions <../example_8/doc/userdoc.rst>
- Example 9: Gazebo classic <../example_9/doc/userdoc.rst>
+ Example 9: Gazebo <../example_9/doc/userdoc.rst>
Example 10: Industrial robot with GPIO interfaces <../example_10/doc/userdoc.rst>
Example 11: CarlikeBot <../example_11/doc/userdoc.rst>
Example 12: Controller chaining <../example_12/doc/userdoc.rst>
diff --git a/example_9/bringup/launch/rrbot_gazebo_classic.launch.py b/example_9/bringup/launch/rrbot_gazebo.launch.py
similarity index 86%
rename from example_9/bringup/launch/rrbot_gazebo_classic.launch.py
rename to example_9/bringup/launch/rrbot_gazebo.launch.py
index 1fd754f77..0f7c185a5 100644
--- a/example_9/bringup/launch/rrbot_gazebo_classic.launch.py
+++ b/example_9/bringup/launch/rrbot_gazebo.launch.py
@@ -36,11 +36,26 @@ def generate_launch_description():
# Initialize Arguments
gui = LaunchConfiguration("gui")
+ # gazebo
gazebo = IncludeLaunchDescription(
PythonLaunchDescriptionSource(
- [PathJoinSubstitution([FindPackageShare("gazebo_ros"), "launch", "gazebo.launch.py"])]
+ [FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
),
- launch_arguments={"verbose": "false"}.items(),
+ launch_arguments={"gz_args": " -r -v 3 empty.sdf"}.items(),
+ )
+
+ gz_spawn_entity = Node(
+ package="ros_gz_sim",
+ executable="create",
+ output="screen",
+ arguments=[
+ "-topic",
+ "/robot_description",
+ "-name",
+ "rrbot_system_position",
+ "-allow_renaming",
+ "true",
+ ],
)
# Get URDF via xacro
@@ -52,7 +67,7 @@ def generate_launch_description():
[FindPackageShare("ros2_control_demo_example_9"), "urdf", "rrbot.urdf.xacro"]
),
" ",
- "use_gazebo_classic:=true",
+ "use_gazebo:=true",
]
)
robot_description = {"robot_description": robot_description_content}
@@ -67,13 +82,6 @@ def generate_launch_description():
parameters=[robot_description],
)
- spawn_entity = Node(
- package="gazebo_ros",
- executable="spawn_entity.py",
- arguments=["-topic", "robot_description", "-entity", "rrbot_system_position"],
- output="screen",
- )
-
joint_state_broadcaster_spawner = Node(
package="controller_manager",
executable="spawner",
@@ -97,7 +105,7 @@ def generate_launch_description():
nodes = [
gazebo,
node_robot_state_publisher,
- spawn_entity,
+ gz_spawn_entity,
joint_state_broadcaster_spawner,
robot_controller_spawner,
rviz_node,
diff --git a/example_9/description/gazebo/rrbot.gazebo.xacro b/example_9/description/gazebo/rrbot.gazebo.xacro
index 1de74bcc8..92a6727c8 100644
--- a/example_9/description/gazebo/rrbot.gazebo.xacro
+++ b/example_9/description/gazebo/rrbot.gazebo.xacro
@@ -9,7 +9,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
-
+
$(find ros2_control_demo_example_9)/config/rrbot_controllers.yaml
diff --git a/example_9/description/ros2_control/rrbot.ros2_control.xacro b/example_9/description/ros2_control/rrbot.ros2_control.xacro
index 0d57bf036..dbca1f636 100644
--- a/example_9/description/ros2_control/rrbot.ros2_control.xacro
+++ b/example_9/description/ros2_control/rrbot.ros2_control.xacro
@@ -1,14 +1,14 @@
-
+
-
- gazebo_ros2_control/GazeboSystem
+
+ gz_ros2_control/GazeboSimSystem
-
+
ros2_control_demo_example_9/RRBotSystemPositionOnlyHardware
0
3.0
diff --git a/example_9/description/urdf/rrbot.urdf.xacro b/example_9/description/urdf/rrbot.urdf.xacro
index a77033cee..3dbb012b3 100644
--- a/example_9/description/urdf/rrbot.urdf.xacro
+++ b/example_9/description/urdf/rrbot.urdf.xacro
@@ -6,7 +6,7 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
-->
-
+
@@ -25,9 +25,9 @@ https://github.com/ros-simulation/gazebo_ros_demos/blob/kinetic-devel/rrbot_desc
+ name="RRBot" prefix="$(arg prefix)" use_gazebo="$(arg use_gazebo)"/>
-
+
diff --git a/example_9/doc/rrbot_gazebo.png b/example_9/doc/rrbot_gazebo.png
new file mode 100644
index 000000000..3952e0bd0
Binary files /dev/null and b/example_9/doc/rrbot_gazebo.png differ
diff --git a/example_9/doc/rrbot_gazebo_classic.png b/example_9/doc/rrbot_gazebo_classic.png
deleted file mode 100644
index 783c934c6..000000000
Binary files a/example_9/doc/rrbot_gazebo_classic.png and /dev/null differ
diff --git a/example_9/doc/userdoc.rst b/example_9/doc/userdoc.rst
index 3e612d1ee..363e950d2 100644
--- a/example_9/doc/userdoc.rst
+++ b/example_9/doc/userdoc.rst
@@ -6,34 +6,12 @@ Example 9: Simulation with RRBot
=================================
With *example_9*, we demonstrate the interaction of simulators with ros2_control. More specifically,
-Gazebo Classic is used for this purpose.
+gazebo is used for this purpose.
.. note::
Follow the installation instructions on :ref:`ros2_control_demos_install` how to install all dependencies,
- Gazebo Classic should be automatically installed.
-
- * If you have installed and compiled this repository locally, you can directly use the commands below.
- * 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
-
- .. code::
-
- 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
-
- first. Then on your local machine you can run the Gazebo Classic client with
-
- .. code-block:: shell
-
- gzclient
-
- and/or ``rviz2`` with
-
- .. code-block:: shell
-
- rviz2 -d src/ros2_control_demos/example_9/description/rviz/rrbot.rviz
-
-
- For details on the ``gazebo_ros2_control`` plugin, see :ref:`gazebo_ros2_control`.
+ gazebo should be automatically installed. For details on the ``gz_ros2_control`` plugin, see :ref:`gz_ros2_control`.
Tutorial steps
--------------------------
@@ -55,24 +33,18 @@ Tutorial steps
It uses an identical hardware interface as already discussed with *example_1*, see its docs on details on the hardware interface.
-3. To start *RRBot* in the simulators, open a terminal, source your ROS2-workspace and Gazebo Classic installation first, i.e., by
-
- .. code-block:: shell
-
- source /usr/share/gazebo/setup.sh
-
- Then, execute the launch file with
+3. To start *RRBot* in the simulators, open a terminal, source your ROS2-workspace first. Then, execute the launch file with
.. code-block:: shell
- ros2 launch ros2_control_demo_example_9 rrbot_gazebo_classic.launch.py gui:=true
+ ros2 launch ros2_control_demo_example_9 rrbot_gazebo.launch.py gui:=true
- The launch file loads the robot description, starts Gazebo Classic, *Joint State Broadcaster* and *Forward Command Controller*.
- If you can see two orange and one yellow "box" in Gazebo Classic everything has started properly.
+ The launch file loads the robot description, starts gazebo, *Joint State Broadcaster* and *Forward Command Controller*.
+ If you can see two orange and one yellow "box" in gazebo everything has started properly.
- .. image:: rrbot_gazebo_classic.png
+ .. image:: rrbot_gazebo.png
:width: 400
- :alt: Revolute-Revolute Manipulator Robot in Gazebo Classic
+ :alt: Revolute-Revolute Manipulator Robot in gazebo
4. Check if the hardware interface loaded properly, by opening another terminal and executing
@@ -118,7 +90,7 @@ Tutorial steps
ros2 launch ros2_control_demo_example_9 test_forward_position_controller.launch.py
- You should now see the robot moving in Gazebo Classic.
+ You should now see the robot moving in gazebo.
If you echo the ``/joint_states`` or ``/dynamic_joint_states`` topics you should see the changing values,
namely the simulated states of the robot
@@ -135,7 +107,7 @@ Files used for this demos
- Launch files:
+ Hardware: `rrbot.launch.py `__
- + Gazebo Classic: `rrbot_gazebo_classic.launch.py `__
+ + gazebo: `rrbot_gazebo.launch.py `__
- Controllers yaml: `rrbot_controllers.yaml `__
- URDF file: `rrbot.urdf.xacro `__
diff --git a/example_9/package.xml b/example_9/package.xml
index 580b31746..5d289b25e 100644
--- a/example_9/package.xml
+++ b/example_9/package.xml
@@ -23,8 +23,8 @@
controller_manager
forward_command_controller
- gazebo_ros
- gazebo_ros2_control
+ ros_gz_sim
+ gz_ros2_control
joint_state_broadcaster
joint_state_publisher_gui
joint_trajectory_controller
diff --git a/ros2_control_demos.rolling.repos b/ros2_control_demos.rolling.repos
index 4b0771038..e2024e5ee 100644
--- a/ros2_control_demos.rolling.repos
+++ b/ros2_control_demos.rolling.repos
@@ -15,7 +15,7 @@ repositories:
type: git
url: https://github.com/ros-controls/ros2_controllers.git
version: master
- gazebo_ros2_control:
+ gz_ros2_control:
type: git
- url: https://github.com/ros-controls/gazebo_ros2_control.git
+ url: https://github.com/ros-controls/gz_ros2_control.git
version: master