diff --git a/moveit_ros/moveit_servo/tests/launch/servo_cpp_integration.test.py b/moveit_ros/moveit_servo/tests/launch/servo_cpp_integration.test.py index 99c45de1f8..6cb56bfa5b 100644 --- a/moveit_ros/moveit_servo/tests/launch/servo_cpp_integration.test.py +++ b/moveit_ros/moveit_servo/tests/launch/servo_cpp_integration.test.py @@ -76,7 +76,7 @@ def generate_test_description(): package="tf2_ros", plugin="tf2_ros::StaticTransformBroadcasterNode", name="static_tf2_broadcaster", - parameters=[{"/child_frame_id": "panda_link0", "/frame_id": "world"}], + parameters=[{"child_frame_id": "/panda_link0", "frame_id": "/world"}], ), ], output="screen", diff --git a/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp b/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp index c950240299..26f78362cc 100644 --- a/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp +++ b/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp @@ -75,7 +75,6 @@ class ServoRosFixture : public testing::Test { // Create a node to be given to Servo. servo_test_node_ = std::make_shared("moveit_servo_test"); - executor_ = std::make_shared(); status_ = moveit_servo::StatusCode::INVALID; @@ -96,13 +95,14 @@ class ServoRosFixture : public testing::Test waitForService(); - executor_->add_node(servo_test_node_); - executor_thread_ = std::thread([this]() { executor_->spin(); }); + executor_.add_node(servo_test_node_); + executor_thread_ = std::thread([this]() { executor_.spin(); }); } void TearDown() override { - executor_->cancel(); + executor_.remove_node(servo_test_node_); + executor_.cancel(); if (executor_thread_.joinable()) { executor_thread_.join(); @@ -122,7 +122,7 @@ class ServoRosFixture : public testing::Test rclcpp::sleep_for(std::chrono::milliseconds(500)); } - RCLCPP_INFO(logger, "SERVICE READY"); + RCLCPP_INFO(logger, "MoveIt Servo input switching service ready!"); } void waitForJointStates() @@ -150,7 +150,7 @@ class ServoRosFixture : public testing::Test std::shared_ptr servo_test_node_; // Executor and a thread to run the executor. - rclcpp::Executor::SharedPtr executor_; + rclcpp::executors::SingleThreadedExecutor executor_; std::thread executor_thread_; rclcpp::Subscription::SharedPtr status_subscriber_;