Skip to content

Commit

Permalink
Fix executor to avoid random exceptions when shutting down (#1212)
Browse files Browse the repository at this point in the history
* Fix executor to avoid random exceptions when shutting down

Signed-off-by: Ivan Santiago Paunovic <[email protected]>

* Add link to related issue in rclcpp

Signed-off-by: Ivan Santiago Paunovic <[email protected]>
  • Loading branch information
ivanpauno authored and jacobperron committed Feb 3, 2021
1 parent e6c6376 commit 35172df
Showing 1 changed file with 13 additions and 4 deletions.
17 changes: 13 additions & 4 deletions gazebo_ros/src/executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -22,15 +22,22 @@ namespace gazebo_ros
Executor::Executor()
: spin_thread_(std::bind(&Executor::run, this))
{
using namespace std::chrono_literals;
sigint_handle_ = gazebo::event::Events::ConnectSigInt(std::bind(&Executor::shutdown, this));
while (!this->spinning) {
// TODO(ivanpauno): WARN Terrible hack here!!!!
// We cannot call rclcpp::shutdown asynchronously, because it generates exceptions that
// cannot be caught properly (see https://github.com/ros2/rclcpp/issues/1139).
// Executor::cancel() doesn't cause this problem, but it has a race.
// Wait until the launched thread starts spinning to avoid the race ...
std::this_thread::sleep_for(100ms);
}
}

Executor::~Executor()
{
// If ros was not already shutdown by SIGINT handler, do it now
if (rclcpp::ok()) {
rclcpp::shutdown();
}
this->shutdown();
spin_thread_.join();
}

Expand All @@ -41,7 +48,9 @@ void Executor::run()

void Executor::shutdown()
{
rclcpp::shutdown();
if (this->spinning) {
this->cancel();
}
}

} // namespace gazebo_ros

0 comments on commit 35172df

Please sign in to comment.