diff --git a/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp b/moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp index 8ba123be94..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,14 +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_->remove_node(servo_test_node_); - executor_->cancel(); + executor_.remove_node(servo_test_node_); + executor_.cancel(); if (executor_thread_.joinable()) { executor_thread_.join(); @@ -151,7 +150,7 @@ class ServoRosFixture : public testing::Test std::shared_ptr servo_test_node_; // Executor and a thread to run the executor. - std::shared_ptr executor_; + rclcpp::executors::SingleThreadedExecutor executor_; std::thread executor_thread_; rclcpp::Subscription::SharedPtr status_subscriber_;