Skip to content

Commit f7b6654

Browse files
Fix lifecycle manager deadlock during shutdown (#5438)
* Fix lifecycle manager deadlock during shutdown Add stop() method to ServiceClient that cancels internal executor operations and call it in LifecycleServiceClient destructor to prevent deadlock when CTRL+C is pressed during lifecycle node bringup. This addresses issue #5437 where spin_until_future_complete can hang indefinitely during shutdown when bringup and shutdown sequences run concurrently. Co-authored-by: Steve Macenski <[email protected]> * Update service_client.hpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com>
1 parent 935ffb9 commit f7b6654

File tree

2 files changed

+16
-0
lines changed

2 files changed

+16
-0
lines changed

nav2_ros_common/include/nav2_ros_common/service_client.hpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -218,6 +218,16 @@ class ServiceClient
218218
return service_name_;
219219
}
220220

221+
/**
222+
* @brief Stop any running spin operations on the internal executor
223+
*/
224+
void stop()
225+
{
226+
if (client_) {
227+
callback_group_executor_->cancel();
228+
}
229+
}
230+
221231
protected:
222232
std::string service_name_;
223233
rclcpp::Clock::SharedPtr clock_;

nav2_util/include/nav2_util/lifecycle_service_client.hpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,12 @@ class LifecycleServiceClient
5757
}
5858
}
5959

60+
~LifecycleServiceClient()
61+
{
62+
change_state_.stop();
63+
get_state_.stop();
64+
}
65+
6066
/// Trigger a state change
6167
/**
6268
* Throws std::runtime_error on failure

0 commit comments

Comments
 (0)