Skip to content

Commit

Permalink
Do not remove goal handle from list if result request fails
Browse files Browse the repository at this point in the history
This way the user can still interact with the goal (e.g. send a cancel request).

Signed-off-by: Jacob Perron <jacob@openrobotics.org>
  • Loading branch information
jacobperron committed Sep 14, 2020
1 parent 3f8fc43 commit 81239f1
Showing 1 changed file with 1 addition and 2 deletions.
3 changes: 1 addition & 2 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -643,9 +643,8 @@ class Client : public ClientBase
goal_handles_.erase(goal_handle->get_goal_id());
});
} catch (rclcpp::exceptions::RCLError &) {
// This will cause an exception when the user tries to access the result
goal_handle->invalidate();
std::lock_guard<std::mutex> lock(goal_handles_mutex_);
goal_handles_.erase(goal_handle->get_goal_id());
}
}

Expand Down

0 comments on commit 81239f1

Please sign in to comment.