Skip to content

Commit 4401b88

Browse files
Activate integration test of gazebo example 9 (#759)
1 parent 2587970 commit 4401b88

File tree

5 files changed

+121
-5
lines changed

5 files changed

+121
-5
lines changed

example_9/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,7 @@ if(BUILD_TESTING)
7373
ament_add_pytest_test(example_9_urdf_xacro test/test_urdf_xacro.py)
7474
ament_add_pytest_test(view_example_9_launch test/test_view_robot_launch.py)
7575
ament_add_pytest_test(run_example_9_launch test/test_rrbot_launch.py)
76+
ament_add_pytest_test(run_example_9_gazebo_launch test/test_rrbot_gazebo_launch.py)
7677
endif()
7778

7879
## EXPORTS

example_9/bringup/launch/rrbot_gazebo.launch.py

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414

1515
from launch import LaunchDescription
1616
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
17-
from launch.conditions import IfCondition
17+
from launch.conditions import IfCondition, UnlessCondition
1818
from launch.launch_description_sources import PythonLaunchDescriptionSource
1919
from launch.substitutions import Command, FindExecutable, PathJoinSubstitution, LaunchConfiguration
2020
from launch_ros.actions import Node
@@ -28,7 +28,7 @@ def generate_launch_description():
2828
declared_arguments.append(
2929
DeclareLaunchArgument(
3030
"gui",
31-
default_value="false",
31+
default_value="true",
3232
description="Start RViz2 automatically with this launch file.",
3333
)
3434
)
@@ -41,7 +41,15 @@ def generate_launch_description():
4141
PythonLaunchDescriptionSource(
4242
[FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
4343
),
44-
launch_arguments={"gz_args": " -r -v 3 empty.sdf"}.items(),
44+
launch_arguments=[("gz_args", " -r -v 3 empty.sdf")],
45+
condition=IfCondition(gui),
46+
)
47+
gazebo_headless = IncludeLaunchDescription(
48+
PythonLaunchDescriptionSource(
49+
[FindPackageShare("ros_gz_sim"), "/launch/gz_sim.launch.py"]
50+
),
51+
launch_arguments=[("gz_args", ["--headless-rendering -s -r -v 3 empty.sdf"])],
52+
condition=UnlessCondition(gui),
4553
)
4654

4755
# Gazebo bridge
@@ -121,6 +129,7 @@ def generate_launch_description():
121129

122130
nodes = [
123131
gazebo,
132+
gazebo_headless,
124133
gazebo_bridge,
125134
node_robot_state_publisher,
126135
gz_spawn_entity,

example_9/doc/userdoc.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -37,7 +37,7 @@ Tutorial steps
3737

3838
.. code-block:: shell
3939
40-
ros2 launch ros2_control_demo_example_9 rrbot_gazebo.launch.py gui:=true
40+
ros2 launch ros2_control_demo_example_9 rrbot_gazebo.launch.py
4141
4242
The launch file loads the robot description, starts gazebo, *Joint State Broadcaster* and *Forward Command Controller*.
4343
If you can see two orange and one yellow "box" in gazebo everything has started properly.
Lines changed: 107 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,107 @@
1+
# Copyright (c) 2025 AIT - Austrian Institute of Technology GmbH
2+
#
3+
# Redistribution and use in source and binary forms, with or without
4+
# modification, are permitted provided that the following conditions are met:
5+
#
6+
# * Redistributions of source code must retain the above copyright
7+
# notice, this list of conditions and the following disclaimer.
8+
#
9+
# * Redistributions in binary form must reproduce the above copyright
10+
# notice, this list of conditions and the following disclaimer in the
11+
# documentation and/or other materials provided with the distribution.
12+
#
13+
# * Neither the name of the {copyright_holder} nor the names of its
14+
# contributors may be used to endorse or promote products derived from
15+
# this software without specific prior written permission.
16+
#
17+
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
# POSSIBILITY OF SUCH DAMAGE.
28+
#
29+
# Author: Christoph Froehlich
30+
31+
import os
32+
import pytest
33+
import unittest
34+
35+
from ament_index_python.packages import get_package_share_directory
36+
from launch import LaunchDescription
37+
from launch.actions import IncludeLaunchDescription
38+
from launch.launch_description_sources import PythonLaunchDescriptionSource
39+
from launch_testing.actions import ReadyToTest
40+
41+
# import launch_testing.markers
42+
import rclpy
43+
from controller_manager.test_utils import (
44+
check_controllers_running,
45+
check_if_js_published,
46+
check_node_running,
47+
)
48+
import psutil
49+
50+
51+
# Executes the given launch file and checks if all nodes can be started
52+
@pytest.mark.rostest
53+
def generate_test_description():
54+
launch_include = IncludeLaunchDescription(
55+
PythonLaunchDescriptionSource(
56+
os.path.join(
57+
get_package_share_directory("ros2_control_demo_example_9"),
58+
"launch/rrbot_gazebo.launch.py",
59+
)
60+
),
61+
launch_arguments={"gui": "false"}.items(),
62+
)
63+
64+
return LaunchDescription([launch_include, ReadyToTest()])
65+
66+
67+
# This is our test fixture. Each method is a test case.
68+
# These run alongside the processes specified in generate_test_description()
69+
class TestFixture(unittest.TestCase):
70+
71+
@classmethod
72+
def setUpClass(cls):
73+
rclpy.init()
74+
75+
@classmethod
76+
def tearDownClass(cls):
77+
for proc in psutil.process_iter():
78+
# check whether the process name matches
79+
if proc.name() == "ruby":
80+
proc.kill()
81+
if "gz sim" in proc.name():
82+
proc.kill()
83+
rclpy.shutdown()
84+
85+
def setUp(self):
86+
self.node = rclpy.create_node("test_node")
87+
88+
def test_node_start(self, proc_output):
89+
check_node_running(self.node, "robot_state_publisher")
90+
91+
def test_controller_running(self, proc_output):
92+
cnames = ["forward_position_controller", "joint_state_broadcaster"]
93+
94+
check_controllers_running(self.node, cnames)
95+
96+
def test_check_if_msgs_published(self):
97+
check_if_js_published("/joint_states", ["joint1", "joint2"])
98+
99+
100+
# deactivating because gazebo returns -15 and does not stop properly
101+
# @launch_testing.post_shutdown_test()
102+
# # These tests are run after the processes in generate_test_description() have shutdown.
103+
# class TestDescriptionCraneShutdown(unittest.TestCase):
104+
105+
# def test_exit_codes(self, proc_info):
106+
# """Check if the processes exited normally."""
107+
# launch_testing.asserts.assertExitCodes(proc_info)

example_9/test/test_rrbot_launch.py

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -84,7 +84,6 @@ def test_node_start(self, proc_output):
8484
check_node_running(self.node, "robot_state_publisher")
8585

8686
def test_controller_running(self, proc_output):
87-
8887
cnames = ["forward_position_controller", "joint_state_broadcaster"]
8988

9089
check_controllers_running(self.node, cnames)

0 commit comments

Comments
 (0)