Skip to content

Commit

Permalink
Fix deadlock during shutdown()
Browse files Browse the repository at this point in the history
Needed to release the GIL while blocking on another lock.

Signed-off-by: Brad Martin <[email protected]>
  • Loading branch information
Brad Martin committed Jan 16, 2025
1 parent dde4442 commit aabfc18
Show file tree
Hide file tree
Showing 2 changed files with 32 additions and 28 deletions.
18 changes: 11 additions & 7 deletions rclpy/src/rclpy/events_executor/events_executor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -117,15 +117,19 @@ bool EventsExecutor::shutdown(std::optional<double> timeout)

io_context_.stop();

// Block until spinning is done, or timeout.
std::unique_lock<std::timed_mutex> spin_lock(spinning_mutex_, std::defer_lock);
if (timeout) {
if (!spin_lock.try_lock_for(std::chrono::duration<double>(*timeout))) {
return false;
// Block until spinning is done, or timeout. Release the GIL while we block though.
{
py::gil_scoped_release gil_release;
std::unique_lock<std::timed_mutex> spin_lock(spinning_mutex_, std::defer_lock);
if (timeout) {
if (!spin_lock.try_lock_for(std::chrono::duration<double>(*timeout))) {
return false;
}
} else {
spin_lock.lock();
}
} else {
spin_lock.lock();
}

// Tear down any callbacks we still have registered.
for (py::handle node : py::list(nodes_)) {
remove_node(node);
Expand Down
42 changes: 21 additions & 21 deletions rclpy/test/test_executor.py
Original file line number Diff line number Diff line change
Expand Up @@ -71,31 +71,31 @@ def test_single_threaded_executor_executes(self) -> None:

def test_executor_immediate_shutdown(self) -> None:
self.assertIsNotNone(self.node.handle)
# TODO(bmartin427) EventsExecutor.shutdown() wedges here, not sure why yet
executor = SingleThreadedExecutor(context=self.context)
try:
got_callback = False
for cls in [SingleThreadedExecutor, EventsExecutor]:
executor = cls(context=self.context)
try:
got_callback = False

def timer_callback() -> None:
nonlocal got_callback
got_callback = True
def timer_callback() -> None:
nonlocal got_callback
got_callback = True

timer_period = 1
tmr = self.node.create_timer(timer_period, timer_callback)
timer_period = 1
tmr = self.node.create_timer(timer_period, timer_callback)

self.assertTrue(executor.add_node(self.node))
t = threading.Thread(target=executor.spin, daemon=True)
start_time = time.monotonic()
t.start()
executor.shutdown()
t.join()
end_time = time.monotonic()
self.assertTrue(executor.add_node(self.node))
t = threading.Thread(target=executor.spin, daemon=True)
start_time = time.monotonic()
t.start()
executor.shutdown()
t.join()
end_time = time.monotonic()

self.node.destroy_timer(tmr)
self.assertLess(end_time - start_time, timer_period / 2)
self.assertFalse(got_callback)
finally:
executor.shutdown()
self.node.destroy_timer(tmr)
self.assertLess(end_time - start_time, timer_period / 2)
self.assertFalse(got_callback)
finally:
executor.shutdown()

def test_shutdown_executor_before_waiting_for_callbacks(self) -> None:
self.assertIsNotNone(self.node.handle)
Expand Down

0 comments on commit aabfc18

Please sign in to comment.