diff --git a/ros2_controllers_test_nodes/package.xml b/ros2_controllers_test_nodes/package.xml index c53f1b9971..0b97d6bb0c 100644 --- a/ros2_controllers_test_nodes/package.xml +++ b/ros2_controllers_test_nodes/package.xml @@ -21,6 +21,8 @@ trajectory_msgs python3-pytest + launch_testing_ros + launch_ros ament_python diff --git a/ros2_controllers_test_nodes/test/test_publisher_forward_position_controller_launch.py b/ros2_controllers_test_nodes/test/test_publisher_forward_position_controller_launch.py index 8ebb2df7b3..3f4c9da21f 100644 --- a/ros2_controllers_test_nodes/test/test_publisher_forward_position_controller_launch.py +++ b/ros2_controllers_test_nodes/test/test_publisher_forward_position_controller_launch.py @@ -34,15 +34,13 @@ from launch import LaunchDescription from launch.substitutions import PathJoinSubstitution +import launch_ros.actions from launch_ros.substitutions import FindPackageShare from launch_testing.actions import ReadyToTest -from launch_testing_ros import WaitForTopics - import launch_testing.markers +from launch_testing_ros import WaitForTopics import rclpy -import launch_ros.actions from rclpy.node import Node - from std_msgs.msg import Float64MultiArray diff --git a/ros2_controllers_test_nodes/test/test_publisher_joint_trajectory_controller_launch.py b/ros2_controllers_test_nodes/test/test_publisher_joint_trajectory_controller_launch.py index d8d6e2a577..62ad25550d 100644 --- a/ros2_controllers_test_nodes/test/test_publisher_joint_trajectory_controller_launch.py +++ b/ros2_controllers_test_nodes/test/test_publisher_joint_trajectory_controller_launch.py @@ -34,13 +34,12 @@ from launch import LaunchDescription from launch.substitutions import PathJoinSubstitution +import launch_ros.actions from launch_ros.substitutions import FindPackageShare from launch_testing.actions import ReadyToTest -from launch_testing_ros import WaitForTopics - import launch_testing.markers +from launch_testing_ros import WaitForTopics import rclpy -import launch_ros.actions from rclpy.node import Node from trajectory_msgs.msg import JointTrajectory