Skip to content

Commit 0ba16d2

Browse files
Add launch tests to all examples (#540)
* Add test for ex1 * Add test for ex2 * Add test for ex3 * Add test for ex4 * Add missing dependency * Deactivate GUI * Add test for ex5 * Add act stuff to gitignore * Deactivate gui in tests * Reduce update rate to avoid clogging the log * Use set instead of list * Add test for ex6 * Fix xacro macros and add gui launch argument * Add test for example_7 * Add test for example_8 * Add test for example_9 * Add test for example_10 * Add test for example_11 * Add test for example_12 * Add test for example_14 * Update test for example_15 * Add test for example_15 multi_cm * Add missing dependency * Add missing dependency for ex4+ex5 * Robustify tests and reuse methos for launch_testing * Fix dependencies * Use a set to compare the joint names * Reorder controller spawners * Activate assertExitCodes tests * Deactivate failing tests for example_15 * Increase timeout for example_10 * Add backward_ros everywhere * Add error output and update includes * Revert "Activate assertExitCodes tests" This reverts commit fe28c67. * Add missing import * Update ros2_control_demo_testing/package.xml Co-authored-by: Sai Kishor Kothakota <[email protected]> * Reuse check_node_running * Try to robustify example_14 tests --------- Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent f92cc21 commit 0ba16d2

File tree

77 files changed

+1948
-169
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

77 files changed

+1948
-169
lines changed

.gitignore

+2-6
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,2 @@
1-
.kdev4/
2-
3-
4-
*~
5-
*.kate-swp
6-
*.kdev4
1+
.ccache
2+
.work

example_1/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1717
)
1818

1919
# find dependencies
20+
find_package(backward_ros REQUIRED)
2021
find_package(ament_cmake REQUIRED)
2122
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2223
find_package(${Dependency} REQUIRED)
@@ -66,6 +67,7 @@ if(BUILD_TESTING)
6667

6768
ament_add_pytest_test(example_1_urdf_xacro test/test_urdf_xacro.py)
6869
ament_add_pytest_test(view_example_1_launch test/test_view_robot_launch.py)
70+
ament_add_pytest_test(run_example_1_launch test/test_rrbot_launch.py)
6971
endif()
7072

7173

example_1/bringup/launch/rrbot.launch.py

+7-6
Original file line numberDiff line numberDiff line change
@@ -105,20 +105,21 @@ def generate_launch_description():
105105
)
106106
)
107107

108-
# Delay start of robot_controller after `joint_state_broadcaster`
109-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
108+
# Delay start of joint_state_broadcaster after `robot_controller`
109+
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
110+
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
110111
event_handler=OnProcessExit(
111-
target_action=joint_state_broadcaster_spawner,
112-
on_exit=[robot_controller_spawner],
112+
target_action=robot_controller_spawner,
113+
on_exit=[joint_state_broadcaster_spawner],
113114
)
114115
)
115116

116117
nodes = [
117118
control_node,
118119
robot_state_pub_node,
119-
joint_state_broadcaster_spawner,
120+
robot_controller_spawner,
120121
delay_rviz_after_joint_state_broadcaster_spawner,
121-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
122+
delay_joint_state_broadcaster_after_robot_controller_spawner,
122123
]
123124

124125
return LaunchDescription(declared_arguments + nodes)

example_1/package.xml

+2-1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
<buildtool_depend>ament_cmake</buildtool_depend>
1717

18+
<depend>backward_ros</depend>
1819
<depend>hardware_interface</depend>
1920
<depend>pluginlib</depend>
2021
<depend>rclcpp</depend>
@@ -34,9 +35,9 @@
3435
<exec_depend>xacro</exec_depend>
3536

3637
<test_depend>ament_cmake_pytest</test_depend>
37-
<test_depend>launch_testing_ament_cmake</test_depend>
3838
<test_depend>launch_testing_ros</test_depend>
3939
<test_depend>liburdfdom-tools</test_depend>
40+
<test_depend>ros2_control_demo_testing</test_depend>
4041
<test_depend>xacro</test_depend>
4142

4243
<export>

example_1/test/test_rrbot_launch.py

+99
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,99 @@
1+
# Copyright (c) 2024 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 rclpy.node import Node
44+
from ros2_control_demo_testing.test_utils import (
45+
check_controllers_running,
46+
check_if_js_published,
47+
check_node_running,
48+
)
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_1"),
58+
"launch/rrbot.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+
def setUp(self):
72+
rclpy.init()
73+
self.node = Node("test_node")
74+
75+
def tearDown(self):
76+
self.node.destroy_node()
77+
rclpy.shutdown()
78+
79+
def test_node_start(self, proc_output):
80+
check_node_running(self.node, "robot_state_publisher")
81+
82+
def test_controller_running(self, proc_output):
83+
84+
cnames = ["forward_position_controller", "joint_state_broadcaster"]
85+
86+
check_controllers_running(self.node, cnames)
87+
88+
def test_check_if_msgs_published(self):
89+
check_if_js_published("/joint_states", ["joint1", "joint2"])
90+
91+
92+
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
93+
# @launch_testing.post_shutdown_test()
94+
# # These tests are run after the processes in generate_test_description() have shutdown.
95+
# class TestDescriptionCraneShutdown(unittest.TestCase):
96+
97+
# def test_exit_codes(self, proc_info):
98+
# """Check if the processes exited normally."""
99+
# launch_testing.asserts.assertExitCodes(proc_info)

example_10/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
2020
)
2121

2222
# find dependencies
23+
find_package(backward_ros REQUIRED)
2324
find_package(ament_cmake REQUIRED)
2425
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2526
find_package(${Dependency} REQUIRED)
@@ -77,6 +78,7 @@ if(BUILD_TESTING)
7778

7879
ament_add_pytest_test(example_10_urdf_xacro test/test_urdf_xacro.py)
7980
ament_add_pytest_test(view_example_10_launch test/test_view_robot_launch.py)
81+
ament_add_pytest_test(run_example_10_launch test/test_rrbot_launch.py)
8082
endif()
8183

8284
## EXPORTS

example_10/bringup/launch/rrbot.launch.py

+14-7
Original file line numberDiff line numberDiff line change
@@ -93,20 +93,27 @@ def generate_launch_description():
9393
arguments=["gpio_controller", "-c", "/controller_manager"],
9494
)
9595

96-
# Delay start of robot_controller after `joint_state_broadcaster`
97-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
96+
# Delay start of joint_state_broadcaster after `robot_controller`
97+
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
98+
delay_gpio_after_robot_controller_spawner = RegisterEventHandler(
9899
event_handler=OnProcessExit(
99-
target_action=joint_state_broadcaster_spawner,
100-
on_exit=[robot_controller_spawner],
100+
target_action=robot_controller_spawner,
101+
on_exit=[gpio_controller_spawner],
102+
)
103+
)
104+
delay_joint_state_broadcaster_after_gpio_controller_spawner = RegisterEventHandler(
105+
event_handler=OnProcessExit(
106+
target_action=gpio_controller_spawner,
107+
on_exit=[joint_state_broadcaster_spawner],
101108
)
102109
)
103110

104111
nodes = [
105112
control_node,
106113
robot_state_pub_node,
107-
joint_state_broadcaster_spawner,
108-
gpio_controller_spawner,
109-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
114+
robot_controller_spawner,
115+
delay_gpio_after_robot_controller_spawner,
116+
delay_joint_state_broadcaster_after_gpio_controller_spawner,
110117
]
111118

112119
return LaunchDescription(declared_arguments + nodes)

example_10/package.xml

+2-2
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515

1616
<buildtool_depend>ament_cmake</buildtool_depend>
1717

18+
<depend>backward_ros</depend>
1819
<depend>hardware_interface</depend>
1920
<depend>pluginlib</depend>
2021
<depend>rclcpp</depend>
@@ -32,11 +33,10 @@
3233
<exec_depend>rviz2</exec_depend>
3334
<exec_depend>xacro</exec_depend>
3435

35-
<test_depend>ament_cmake_gtest</test_depend>
3636
<test_depend>ament_cmake_pytest</test_depend>
37-
<test_depend>launch_testing_ament_cmake</test_depend>
3837
<test_depend>launch_testing_ros</test_depend>
3938
<test_depend>liburdfdom-tools</test_depend>
39+
<test_depend>ros2_control_demo_testing</test_depend>
4040
<test_depend>xacro</test_depend>
4141

4242
<export>

example_10/test/test_rrbot_launch.py

+104
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,104 @@
1+
# Copyright (c) 2024 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
42+
import rclpy
43+
from rclpy.node import Node
44+
from ros2_control_demo_testing.test_utils import (
45+
check_controllers_running,
46+
check_if_js_published,
47+
check_node_running,
48+
)
49+
50+
51+
# This function specifies the processes to be run for our test
52+
# The ReadyToTest action waits for 15 second by default for the processes to
53+
# start, if processes take more time an error is thrown. We use decorator here
54+
# to provide timeout duration of 20 second so that processes that take longer than
55+
# 15 seconds can start up.
56+
@pytest.mark.launch_test
57+
@launch_testing.ready_to_test_action_timeout(20)
58+
def generate_test_description():
59+
launch_include = IncludeLaunchDescription(
60+
PythonLaunchDescriptionSource(
61+
os.path.join(
62+
get_package_share_directory("ros2_control_demo_example_10"),
63+
"launch/rrbot.launch.py",
64+
)
65+
),
66+
launch_arguments={"gui": "false"}.items(),
67+
)
68+
69+
return LaunchDescription([launch_include, ReadyToTest()])
70+
71+
72+
# This is our test fixture. Each method is a test case.
73+
# These run alongside the processes specified in generate_test_description()
74+
class TestFixture(unittest.TestCase):
75+
76+
def setUp(self):
77+
rclpy.init()
78+
self.node = Node("test_node")
79+
80+
def tearDown(self):
81+
self.node.destroy_node()
82+
rclpy.shutdown()
83+
84+
def test_node_start(self, proc_output):
85+
check_node_running(self.node, "robot_state_publisher")
86+
87+
def test_controller_running(self, proc_output):
88+
89+
cnames = ["forward_position_controller", "gpio_controller", "joint_state_broadcaster"]
90+
91+
check_controllers_running(self.node, cnames)
92+
93+
def test_check_if_msgs_published(self):
94+
check_if_js_published("/joint_states", ["joint1", "joint2"])
95+
96+
97+
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
98+
# @launch_testing.post_shutdown_test()
99+
# # These tests are run after the processes in generate_test_description() have shutdown.
100+
# class TestDescriptionCraneShutdown(unittest.TestCase):
101+
102+
# def test_exit_codes(self, proc_info):
103+
# """Check if the processes exited normally."""
104+
# launch_testing.asserts.assertExitCodes(proc_info)

example_11/CMakeLists.txt

+2
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
1717
)
1818

1919
# find dependencies
20+
find_package(backward_ros REQUIRED)
2021
find_package(ament_cmake REQUIRED)
2122
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
2223
find_package(${Dependency} REQUIRED)
@@ -66,6 +67,7 @@ if(BUILD_TESTING)
6667

6768
ament_add_pytest_test(example_11_urdf_xacro test/test_urdf_xacro.py)
6869
ament_add_pytest_test(view_example_11_launch test/test_view_robot_launch.py)
70+
ament_add_pytest_test(run_example_11_launch test/test_carlikebot_launch.py)
6971
endif()
7072

7173
## EXPORTS

example_11/bringup/launch/carlikebot.launch.py

+7-6
Original file line numberDiff line numberDiff line change
@@ -125,21 +125,22 @@ def generate_launch_description():
125125
)
126126
)
127127

128-
# Delay start of robot_controller after `joint_state_broadcaster`
129-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
128+
# Delay start of joint_state_broadcaster after `robot_controller`
129+
# TODO(anyone): This is a workaround for flaky tests. Remove when fixed.
130+
delay_joint_state_broadcaster_after_robot_controller_spawner = RegisterEventHandler(
130131
event_handler=OnProcessExit(
131-
target_action=joint_state_broadcaster_spawner,
132-
on_exit=[robot_bicycle_controller_spawner],
132+
target_action=robot_bicycle_controller_spawner,
133+
on_exit=[joint_state_broadcaster_spawner],
133134
)
134135
)
135136

136137
nodes = [
137138
control_node,
138139
control_node_remapped,
139140
robot_state_pub_bicycle_node,
140-
joint_state_broadcaster_spawner,
141+
robot_bicycle_controller_spawner,
142+
delay_joint_state_broadcaster_after_robot_controller_spawner,
141143
delay_rviz_after_joint_state_broadcaster_spawner,
142-
delay_robot_controller_spawner_after_joint_state_broadcaster_spawner,
143144
]
144145

145146
return LaunchDescription(declared_arguments + nodes)

0 commit comments

Comments
 (0)