From b8004abca98a6ae717e315dfc7e39fea384e2415 Mon Sep 17 00:00:00 2001 From: Pintaudi Giorgio Date: Mon, 13 Mar 2023 16:25:43 +0900 Subject: [PATCH] Fixed module name in sample file Signed-off-by: Pintaudi Giorgio --- .../test/examples/wait_for_topic_inject_callback.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/launch_testing_ros/test/examples/wait_for_topic_inject_callback.py b/launch_testing_ros/test/examples/wait_for_topic_inject_callback.py index 1e083486..799f7a2e 100644 --- a/launch_testing_ros/test/examples/wait_for_topic_inject_callback.py +++ b/launch_testing_ros/test/examples/wait_for_topic_inject_callback.py @@ -24,7 +24,7 @@ import pytest from std_msgs.msg import String -from axel_launch_testing_ros import WaitForTopics +from launch_testing_ros import WaitForTopics def generate_node():