Skip to content

Commit 79e2a87

Browse files
fix: Fixed race condition in action server between is_ready and take. Backport from rolling ros2#2495
1 parent 9be01cf commit 79e2a87

File tree

4 files changed

+423
-248
lines changed

4 files changed

+423
-248
lines changed

rclcpp_action/include/rclcpp_action/server.hpp

Lines changed: 19 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include <unordered_map>
2323
#include <utility>
2424

25+
#include "action_msgs/srv/cancel_goal.hpp"
2526
#include "rcl/event_callback.h"
2627
#include "rcl_action/action_server.h"
2728
#include "rosidl_runtime_c/action_type_support_struct.h"
@@ -77,6 +78,7 @@ class ServerBase : public rclcpp::Waitable
7778
GoalService,
7879
ResultService,
7980
CancelService,
81+
Expired,
8082
};
8183

8284
RCLCPP_ACTION_PUBLIC
@@ -279,19 +281,29 @@ class ServerBase : public rclcpp::Waitable
279281
/// \internal
280282
RCLCPP_ACTION_PUBLIC
281283
void
282-
execute_goal_request_received(std::shared_ptr<void> & data);
284+
execute_goal_request_received(
285+
rcl_ret_t ret,
286+
rcl_action_goal_info_t goal_info,
287+
rmw_request_id_t request_header,
288+
std::shared_ptr<void> message);
283289

284290
/// Handle a request to cancel goals on the server
285291
/// \internal
286292
RCLCPP_ACTION_PUBLIC
287293
void
288-
execute_cancel_request_received(std::shared_ptr<void> & data);
294+
execute_cancel_request_received(
295+
rcl_ret_t ret,
296+
std::shared_ptr<action_msgs::srv::CancelGoal::Request> request,
297+
rmw_request_id_t request_header);
289298

290299
/// Handle a request to get the result of an action
291300
/// \internal
292301
RCLCPP_ACTION_PUBLIC
293302
void
294-
execute_result_request_received(std::shared_ptr<void> & data);
303+
execute_result_request_received(
304+
rcl_ret_t ret,
305+
std::shared_ptr<void> result_request,
306+
rmw_request_id_t request_header);
295307

296308
/// Handle a timeout indicating a completed goal should be forgotten by the server
297309
/// \internal
@@ -345,7 +357,8 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
345357

346358
/// Signature of a callback that accepts or rejects goal requests.
347359
using GoalCallback = std::function<GoalResponse(
348-
const GoalUUID &, std::shared_ptr<const typename ActionT::Goal>)>;
360+
const GoalUUID &,
361+
std::shared_ptr<const typename ActionT::Goal>)>;
349362
/// Signature of a callback that accepts or rejects requests to cancel a goal.
350363
using CancelCallback = std::function<CancelResponse(std::shared_ptr<ServerGoalHandle<ActionT>>)>;
351364
/// Signature of a callback that is used to notify when the goal has been accepted.
@@ -455,7 +468,8 @@ class Server : public ServerBase, public std::enable_shared_from_this<Server<Act
455468
void
456469
call_goal_accepted_callback(
457470
std::shared_ptr<rcl_action_goal_handle_t> rcl_goal_handle,
458-
GoalUUID uuid, std::shared_ptr<void> goal_request_message) override
471+
GoalUUID uuid,
472+
std::shared_ptr<void> goal_request_message) override
459473
{
460474
std::shared_ptr<ServerGoalHandle<ActionT>> goal_handle;
461475
std::weak_ptr<Server<ActionT>> weak_this = this->shared_from_this();

0 commit comments

Comments
 (0)