From 5a2e4dcb4f18ce1d2223531e57fe1f848f6e399e Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 20 Nov 2024 07:19:38 +0000 Subject: [PATCH] Add missing deps --- ros2_controllers_test_nodes/package.xml | 2 ++ .../test/test_publisher_forward_position_controller_launch.py | 4 +--- .../test/test_publisher_joint_trajectory_controller_launch.py | 3 +-- 3 files changed, 4 insertions(+), 5 deletions(-) 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..2c68a71554 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 @@ -35,14 +35,12 @@ from launch import LaunchDescription from launch.substitutions import PathJoinSubstitution from launch_ros.substitutions import FindPackageShare +import launch_ros.actions from launch_testing.actions import ReadyToTest from launch_testing_ros import WaitForTopics - import launch_testing.markers 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..ac3cbe1154 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 @@ -35,12 +35,11 @@ from launch import LaunchDescription from launch.substitutions import PathJoinSubstitution from launch_ros.substitutions import FindPackageShare +import launch_ros.actions from launch_testing.actions import ReadyToTest from launch_testing_ros import WaitForTopics - import launch_testing.markers import rclpy -import launch_ros.actions from rclpy.node import Node from trajectory_msgs.msg import JointTrajectory