Skip to content

Commit 78d6c0f

Browse files
Activate assertExitCodes for missing tests (#720)
1 parent bea3693 commit 78d6c0f

File tree

3 files changed

+15
-17
lines changed

3 files changed

+15
-17
lines changed

example_1/test/test_rrbot_launch_cli_direct.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
from launch.launch_description_sources import PythonLaunchDescriptionSource
4040
from launch_testing.actions import ReadyToTest
4141

42-
# import launch_testing.markers
42+
import launch_testing.markers
4343
import rclpy
4444
from controller_manager.test_utils import check_controllers_running
4545

@@ -109,11 +109,10 @@ def test_main(self, proc_output):
109109
check_controllers_running(self.node, [cname], state="active")
110110

111111

112-
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
113-
# @launch_testing.post_shutdown_test()
114-
# # These tests are run after the processes in generate_test_description() have shutdown.
115-
# class TestDescriptionCraneShutdown(unittest.TestCase):
112+
@launch_testing.post_shutdown_test()
113+
# These tests are run after the processes in generate_test_description() have shutdown.
114+
class TestDescriptionCraneShutdown(unittest.TestCase):
116115

117-
# def test_exit_codes(self, proc_info):
118-
# """Check if the processes exited normally."""
119-
# launch_testing.asserts.assertExitCodes(proc_info)
116+
def test_exit_codes(self, proc_info):
117+
"""Check if the processes exited normally."""
118+
launch_testing.asserts.assertExitCodes(proc_info)

example_11/test/test_carlikebot_launch_remapped.py

Lines changed: 7 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@
3939
from launch_testing.actions import ReadyToTest
4040
from launch_testing_ros import WaitForTopics
4141

42-
# import launch_testing.markers
42+
import launch_testing.markers
4343
import rclpy
4444
from controller_manager.test_utils import (
4545
check_controllers_running,
@@ -110,11 +110,10 @@ def test_remapped_topic(self):
110110
wait_for_topics.shutdown()
111111

112112

113-
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
114-
# @launch_testing.post_shutdown_test()
115-
# # These tests are run after the processes in generate_test_description() have shutdown.
116-
# class TestDescriptionCraneShutdown(unittest.TestCase):
113+
@launch_testing.post_shutdown_test()
114+
# These tests are run after the processes in generate_test_description() have shutdown.
115+
class TestDescriptionCraneShutdown(unittest.TestCase):
117116

118-
# def test_exit_codes(self, proc_info):
119-
# """Check if the processes exited normally."""
120-
# launch_testing.asserts.assertExitCodes(proc_info)
117+
def test_exit_codes(self, proc_info):
118+
"""Check if the processes exited normally."""
119+
launch_testing.asserts.assertExitCodes(proc_info)

example_14/test/test_rrbot_modular_actuators_without_feedback_sensors_for_position_feedback_launch.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ def test_check_if_msgs_published(self):
9797

9898

9999
# TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore
100-
# see https://github.com/ros-controls/ros2_control_demos/issues/542
100+
# see https://github.com/ros-controls/ros2_control_demos/issues/721
101101
# @launch_testing.post_shutdown_test()
102102
# # These tests are run after the processes in generate_test_description() have shutdown.
103103
# class TestDescriptionCraneShutdown(unittest.TestCase):

0 commit comments

Comments
 (0)