Skip to content

Commit

Permalink
Changed to use spin instead of spin_once to enable multithreading wit…
Browse files Browse the repository at this point in the history
…h MultiThreadedExecutor (#315)

Co-authored-by: Alejandro Hernández Cordero <[email protected]>
(cherry picked from commit 4503507)
  • Loading branch information
TakashiSato authored and mergify[bot] committed Jun 3, 2024
1 parent b8a28fd commit 382c563
Showing 1 changed file with 1 addition and 8 deletions.
9 changes: 1 addition & 8 deletions ign_ros2_control/src/ign_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,6 @@ class IgnitionROS2ControlPluginPrivate
/// \brief Thread where the executor will spin
std::thread thread_executor_spin_;

/// \brief Flag to stop the executor thread when this plugin is exiting
bool stop_{false};

/// \brief Executor to spin the controller
rclcpp::executors::MultiThreadedExecutor::SharedPtr executor_;

Expand Down Expand Up @@ -238,7 +235,6 @@ IgnitionROS2ControlPlugin::IgnitionROS2ControlPlugin()
IgnitionROS2ControlPlugin::~IgnitionROS2ControlPlugin()
{
// Stop controller manager thread
this->dataPtr->stop_ = true;
this->dataPtr->executor_->remove_node(this->dataPtr->controller_manager_);
this->dataPtr->executor_->cancel();
this->dataPtr->thread_executor_spin_.join();
Expand Down Expand Up @@ -354,12 +350,9 @@ void IgnitionROS2ControlPlugin::Configure(
this->dataPtr->node_ = rclcpp::Node::make_shared(node_name, ns);
this->dataPtr->executor_ = std::make_shared<rclcpp::executors::MultiThreadedExecutor>();
this->dataPtr->executor_->add_node(this->dataPtr->node_);
this->dataPtr->stop_ = false;
auto spin = [this]()
{
while (rclcpp::ok() && !this->dataPtr->stop_) {
this->dataPtr->executor_->spin_once();
}
this->dataPtr->executor_->spin();
};
this->dataPtr->thread_executor_spin_ = std::thread(spin);

Expand Down

0 comments on commit 382c563

Please sign in to comment.