Skip to content

Commit

Permalink
No need for executor to be a shared pointer
Browse files Browse the repository at this point in the history
  • Loading branch information
sea-bass committed Aug 10, 2024
1 parent 9c77015 commit 3b718c7
Showing 1 changed file with 5 additions and 6 deletions.
11 changes: 5 additions & 6 deletions moveit_ros/moveit_servo/tests/servo_ros_fixture.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,6 @@ class ServoRosFixture : public testing::Test
{
// Create a node to be given to Servo.
servo_test_node_ = std::make_shared<rclcpp::Node>("moveit_servo_test");
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();

status_ = moveit_servo::StatusCode::INVALID;

Expand All @@ -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();
Expand Down Expand Up @@ -151,7 +150,7 @@ class ServoRosFixture : public testing::Test
std::shared_ptr<rclcpp::Node> servo_test_node_;

// Executor and a thread to run the executor.
std::shared_ptr<rclcpp::executors::SingleThreadedExecutor> executor_;
rclcpp::executors::SingleThreadedExecutor executor_;
std::thread executor_thread_;

rclcpp::Subscription<moveit_msgs::msg::ServoStatus>::SharedPtr status_subscriber_;
Expand Down

0 comments on commit 3b718c7

Please sign in to comment.