Fix action server deadlock issue that caused by other mutexes locked in CancelCallback (#1635) (#1654)

Signed-off-by: Kaven Yau <kavenyau@foxmail.com>
This commit is contained in:
Kaven Yau 2021-05-05 21:28:42 +08:00 committed by GitHub
parent 6ceeff0f0f
commit 791c23afe5
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23

View file

@ -352,16 +352,20 @@ protected:
CancelResponse CancelResponse
call_handle_cancel_callback(const GoalUUID & uuid) override call_handle_cancel_callback(const GoalUUID & uuid) override
{ {
std::lock_guard<std::mutex> lock(goal_handles_mutex_); std::shared_ptr<ServerGoalHandle<ActionT>> goal_handle;
{
std::lock_guard<std::mutex> lock(goal_handles_mutex_);
auto element = goal_handles_.find(uuid);
if (element != goal_handles_.end()) {
goal_handle = element->second.lock();
}
}
CancelResponse resp = CancelResponse::REJECT; CancelResponse resp = CancelResponse::REJECT;
auto element = goal_handles_.find(uuid); if (goal_handle) {
if (element != goal_handles_.end()) { resp = handle_cancel_(goal_handle);
std::shared_ptr<ServerGoalHandle<ActionT>> goal_handle = element->second.lock(); if (CancelResponse::ACCEPT == resp) {
if (goal_handle) { goal_handle->_cancel_goal();
resp = handle_cancel_(goal_handle);
if (CancelResponse::ACCEPT == resp) {
goal_handle->_cancel_goal();
}
} }
} }
return resp; return resp;