From d99f5327d4c5f8886531608425e42551bebd3b5e Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Sat, 21 Dec 2024 09:54:06 +0000 Subject: [PATCH] Test if remapped topic is still there --- example_11/test/test_carlikebot_launch.py | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/example_11/test/test_carlikebot_launch.py b/example_11/test/test_carlikebot_launch.py index 1afb4ff3..1b45ec0d 100644 --- a/example_11/test/test_carlikebot_launch.py +++ b/example_11/test/test_carlikebot_launch.py @@ -37,6 +37,7 @@ from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource from launch_testing.actions import ReadyToTest +from launch_testing_ros import WaitForTopics # import launch_testing.markers import rclpy @@ -46,6 +47,8 @@ check_node_running, ) +from tf2_msgs.msg import TFMessage + # Executes the given launch file and checks if all nodes can be started @pytest.mark.rostest @@ -98,6 +101,13 @@ def test_check_if_msgs_published(self): ], ) + def test_remapped_topic(self): + # we don't want to implement a tf lookup here + # so just check if the unmapped topic is not published + old_topic = "/bicycle_steering_controller/tf_odometry" + wait_for_topics = WaitForTopics([(old_topic, TFMessage)]) + assert not wait_for_topics.wait(), f"Topic '{old_topic}' found, but should be remapped!" + # TODO(anyone): enable this if shutdown of ros2_control_node does not fail anymore # @launch_testing.post_shutdown_test()