Skip to content

Commit

Permalink
Test test_exit_codes once again
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Jul 22, 2024
1 parent 38ee32f commit 4ae55fa
Showing 1 changed file with 7 additions and 7 deletions.
14 changes: 7 additions & 7 deletions controller_manager/test/test_ros2_control_node_launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_testing.actions import ReadyToTest

import launch_testing.markers
import rclpy
from rclpy.node import Node

Expand Down Expand Up @@ -80,11 +81,10 @@ def test_node_start(self):
assert found, "controller_manager not found!"


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

# def test_exit_codes(self, proc_info):
# """Check if the processes exited normally."""
# launch_testing.asserts.assertExitCodes(proc_info)
def test_exit_codes(self, proc_info):
"""Check if the processes exited normally."""
launch_testing.asserts.assertExitCodes(proc_info)

0 comments on commit 4ae55fa

Please sign in to comment.