Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix MultiThreadedExecutor spinning (backport #315) #319

Merged
merged 1 commit into from
Jun 3, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 1 addition & 8 deletions gz_ros2_control/src/gz_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -73,9 +73,6 @@ class GazeboSimROS2ControlPluginPrivate
/// \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 @@ GazeboSimROS2ControlPlugin::GazeboSimROS2ControlPlugin()
GazeboSimROS2ControlPlugin::~GazeboSimROS2ControlPlugin()
{
// 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 @@ -364,12 +360,9 @@ void GazeboSimROS2ControlPlugin::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
Loading