Skip to content

Commit 64f3ff1

Browse files
ivanpaunojacobperron
authored andcommitted
Fix executor to avoid random exceptions when shutting down (#1212)
* Fix executor to avoid random exceptions when shutting down Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com> * Add link to related issue in rclcpp Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
1 parent 8741f23 commit 64f3ff1

File tree

1 file changed

+13
-4
lines changed

1 file changed

+13
-4
lines changed

gazebo_ros/src/executor.cpp

+13-4
Original file line numberDiff line numberDiff line change
@@ -22,15 +22,22 @@ namespace gazebo_ros
2222
Executor::Executor()
2323
: spin_thread_(std::bind(&Executor::run, this))
2424
{
25+
using namespace std::chrono_literals;
2526
sigint_handle_ = gazebo::event::Events::ConnectSigInt(std::bind(&Executor::shutdown, this));
27+
while (!this->spinning) {
28+
// TODO(ivanpauno): WARN Terrible hack here!!!!
29+
// We cannot call rclcpp::shutdown asynchronously, because it generates exceptions that
30+
// cannot be caught properly (see https://github.com/ros2/rclcpp/issues/1139).
31+
// Executor::cancel() doesn't cause this problem, but it has a race.
32+
// Wait until the launched thread starts spinning to avoid the race ...
33+
std::this_thread::sleep_for(100ms);
34+
}
2635
}
2736

2837
Executor::~Executor()
2938
{
3039
// If ros was not already shutdown by SIGINT handler, do it now
31-
if (rclcpp::ok()) {
32-
rclcpp::shutdown();
33-
}
40+
this->shutdown();
3441
spin_thread_.join();
3542
}
3643

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

4249
void Executor::shutdown()
4350
{
44-
rclcpp::shutdown();
51+
if (this->spinning) {
52+
this->cancel();
53+
}
4554
}
4655

4756
} // namespace gazebo_ros

0 commit comments

Comments
 (0)