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

Join with the controller manager's executor thread on exit #79

Merged
merged 4 commits into from
May 31, 2021
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
12 changes: 11 additions & 1 deletion gazebo_ros2_control/src/gazebo_ros2_control_plugin.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,9 @@ class GazeboRosControlPrivate
// Thread where the executor will sping
std::thread thread_executor_spin_;

// Flag to stop the executor thread when this plugin is exiting
bool stop_;

// Controller manager
std::shared_ptr<controller_manager::ControllerManager> controller_manager_;

Expand All @@ -122,6 +125,12 @@ GazeboRosControlPlugin::GazeboRosControlPlugin()

GazeboRosControlPlugin::~GazeboRosControlPlugin()
{
// Stop controller manager thread
impl_->stop_ = true;
impl_->executor_->remove_node(impl_->controller_manager_);
impl_->executor_->cancel();
impl_->thread_executor_spin_.join();

// Disconnect from gazebo events
impl_->update_connection_.reset();
}
Expand Down Expand Up @@ -303,9 +312,10 @@ void GazeboRosControlPlugin::Load(gazebo::physics::ModelPtr parent, sdf::Element
gazebo_period.seconds() << " s).");
}

impl_->stop_ = false;
auto spin = [this]()
{
while (rclcpp::ok()) {
while (rclcpp::ok() && !impl_->stop_) {
impl_->executor_->spin_once();
}
};
Expand Down