rclcpp_action  master
C++ ROS Action Client Library
client.hpp
Go to the documentation of this file.
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef RCLCPP_ACTION__CLIENT_HPP_
16 #define RCLCPP_ACTION__CLIENT_HPP_
17 
18 #include <rclcpp/macros.hpp>
22 #include <rclcpp/logger.hpp>
23 #include <rclcpp/time.hpp>
24 #include <rclcpp/waitable.hpp>
25 
26 #include <rosidl_generator_c/action_type_support_struct.h>
27 #include <rosidl_typesupport_cpp/action_type_support.hpp>
28 
29 #include <algorithm>
30 #include <chrono>
31 #include <functional>
32 #include <future>
33 #include <map>
34 #include <memory>
35 #include <mutex>
36 #include <string>
37 #include <utility>
38 
40 #include "rclcpp_action/types.hpp"
42 
43 
44 namespace rclcpp_action
45 {
46 // Forward declaration
47 class ClientBaseImpl;
48 
51 
58 {
59 public:
61  virtual ~ClientBase();
62 
65  bool
66  action_server_is_ready() const;
67 
69  template<typename RepT = int64_t, typename RatioT = std::milli>
70  bool
73  {
75  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
76  );
77  }
78 
79  // -------------
80  // Waitables API
81 
84  size_t
86 
89  size_t
90  get_number_of_ready_timers() override;
91 
94  size_t
95  get_number_of_ready_clients() override;
96 
99  size_t
100  get_number_of_ready_services() override;
101 
104  size_t
106 
109  bool
110  add_to_wait_set(rcl_wait_set_t * wait_set) override;
111 
114  bool
115  is_ready(rcl_wait_set_t * wait_set) override;
116 
119  void
120  execute() override;
121 
122  // End Waitables API
123  // -----------------
124 
125 protected:
127  ClientBase(
128  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
129  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
130  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
131  const std::string & action_name,
132  const rosidl_action_type_support_t * type_support,
133  const rcl_action_client_options_t & options);
134 
137  bool
139 
140  // -----------------------------------------------------
141  // API for communication between ClientBase and Client<>
143 
147 
150  virtual
151  GoalUUID
153 
156  virtual
157  void
159  std::shared_ptr<void> request,
160  ResponseCallback callback);
161 
164  virtual
165  void
167  std::shared_ptr<void> request,
168  ResponseCallback callback);
169 
172  virtual
173  void
175  std::shared_ptr<void> request,
176  ResponseCallback callback);
177 
179  virtual
181  create_goal_response() const = 0;
182 
185  virtual
186  void
188  const rmw_request_id_t & response_header,
189  std::shared_ptr<void> goal_response);
190 
192  virtual
194  create_result_response() const = 0;
195 
198  virtual
199  void
201  const rmw_request_id_t & response_header,
202  std::shared_ptr<void> result_response);
203 
205  virtual
207  create_cancel_response() const = 0;
208 
211  virtual
212  void
214  const rmw_request_id_t & response_header,
215  std::shared_ptr<void> cancel_response);
216 
218  virtual
220  create_feedback_message() const = 0;
221 
223  virtual
224  void
226 
228  virtual
230  create_status_message() const = 0;
231 
233  virtual
234  void
236 
237  // End API for communication between ClientBase and Client<>
238  // ---------------------------------------------------------
239 
240 private:
242 };
243 
245 
254 template<typename ActionT>
255 class Client : public ClientBase
256 {
257 public:
259 
260  using Goal = typename ActionT::Goal;
261  using Feedback = typename ActionT::Feedback;
262  using GoalHandle = ClientGoalHandle<ActionT>;
264  using GoalResponseCallback =
265  std::function<void (std::shared_future<typename GoalHandle::SharedPtr>)>;
268  using CancelRequest = typename ActionT::Impl::CancelGoalService::Request;
269  using CancelResponse = typename ActionT::Impl::CancelGoalService::Response;
270  using CancelCallback = std::function<void (typename CancelResponse::SharedPtr)>;
271 
273 
277  {
279  : goal_response_callback(nullptr),
280  feedback_callback(nullptr),
281  result_callback(nullptr)
282  {
283  }
284 
286 
295 
297  FeedbackCallback feedback_callback;
298 
300  ResultCallback result_callback;
301  };
302 
304 
316  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
317  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
318  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
319  const std::string & action_name,
321  )
322  : ClientBase(
323  node_base, node_graph, node_logging, action_name,
324  rosidl_typesupport_cpp::get_action_type_support_handle<ActionT>(),
325  client_options)
326  {
327  }
328 
330 
343  async_send_goal(const Goal & goal, const SendGoalOptions & options = SendGoalOptions())
344  {
345  // Put promise in the heap to move it around.
346  auto promise = std::make_shared<std::promise<typename GoalHandle::SharedPtr>>();
347  std::shared_future<typename GoalHandle::SharedPtr> future(promise->get_future());
348  using GoalRequest = typename ActionT::Impl::SendGoalService::Request;
349  auto goal_request = std::make_shared<GoalRequest>();
350  goal_request->goal_id.uuid = this->generate_goal_id();
351  goal_request->goal = goal;
352  this->send_goal_request(
353  std::static_pointer_cast<void>(goal_request),
354  [this, goal_request, options, promise, future](std::shared_ptr<void> response) mutable
355  {
356  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
357  auto goal_response = std::static_pointer_cast<GoalResponse>(response);
358  if (!goal_response->accepted) {
359  promise->set_value(nullptr);
360  if (options.goal_response_callback) {
361  options.goal_response_callback(future);
362  }
363  return;
364  }
365  GoalInfo goal_info;
366  goal_info.goal_id.uuid = goal_request->goal_id.uuid;
367  goal_info.stamp = goal_response->stamp;
368  // Do not use std::make_shared as friendship cannot be forwarded.
369  std::shared_ptr<GoalHandle> goal_handle(
370  new GoalHandle(goal_info, options.feedback_callback, options.result_callback));
371  {
372  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
373  goal_handles_[goal_handle->get_goal_id()] = goal_handle;
374  }
375  promise->set_value(goal_handle);
376  if (options.goal_response_callback) {
377  options.goal_response_callback(future);
378  }
379 
380  if (options.result_callback) {
381  try {
382  this->make_result_aware(goal_handle);
383  } catch (...) {
384  promise->set_exception(std::current_exception());
385  return;
386  }
387  }
388  });
389  return future;
390  }
391 
393 
402  typename GoalHandle::SharedPtr goal_handle,
403  ResultCallback result_callback = nullptr)
404  {
405  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
406  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
408  }
409  if (result_callback) {
410  // This will override any previously registered callback
411  goal_handle->set_result_callback(result_callback);
412  }
413  this->make_result_aware(goal_handle);
414  return goal_handle->async_result();
415  }
416 
418 
432  typename GoalHandle::SharedPtr goal_handle,
433  CancelCallback cancel_callback = nullptr)
434  {
435  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
436  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
438  }
439  auto cancel_request = std::make_shared<CancelRequest>();
440  // cancel_request->goal_info.goal_id = goal_handle->get_goal_id();
441  cancel_request->goal_info.goal_id.uuid = goal_handle->get_goal_id();
442  return async_cancel(cancel_request, cancel_callback);
443  }
444 
446 
456  async_cancel_all_goals(CancelCallback cancel_callback = nullptr)
457  {
458  auto cancel_request = std::make_shared<CancelRequest>();
459  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
460  std::fill(
461  cancel_request->goal_info.goal_id.uuid.begin(),
462  cancel_request->goal_info.goal_id.uuid.end(), 0u);
463  return async_cancel(cancel_request, cancel_callback);
464  }
465 
467 
479  const rclcpp::Time & stamp,
480  CancelCallback cancel_callback = nullptr)
481  {
482  auto cancel_request = std::make_shared<CancelRequest>();
483  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
484  std::fill(
485  cancel_request->goal_info.goal_id.uuid.begin(),
486  cancel_request->goal_info.goal_id.uuid.end(), 0u);
487  cancel_request->goal_info.stamp = stamp;
488  return async_cancel(cancel_request, cancel_callback);
489  }
490 
491  virtual
493  {
494  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
495  auto it = goal_handles_.begin();
496  while (it != goal_handles_.end()) {
497  it->second->invalidate();
498  it = goal_handles_.erase(it);
499  }
500  }
501 
502 private:
505  create_goal_response() const override
506  {
507  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
508  return std::shared_ptr<void>(new GoalResponse());
509  }
510 
513  create_result_response() const override
514  {
515  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
516  return std::shared_ptr<void>(new GoalResultResponse());
517  }
518 
521  create_cancel_response() const override
522  {
524  }
525 
528  create_feedback_message() const override
529  {
530  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
531  return std::shared_ptr<void>(new FeedbackMessage());
532  }
533 
535  void
537  {
538  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
539  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
540  typename FeedbackMessage::SharedPtr feedback_message =
541  std::static_pointer_cast<FeedbackMessage>(message);
542  const GoalUUID & goal_id = feedback_message->goal_id.uuid;
543  if (goal_handles_.count(goal_id) == 0) {
544  RCLCPP_DEBUG(
545  this->get_logger(),
546  "Received feedback for unknown goal. Ignoring...");
547  return;
548  }
549  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id];
550  auto feedback = std::make_shared<Feedback>();
551  *feedback = feedback_message->feedback;
552  goal_handle->call_feedback_callback(goal_handle, feedback);
553  }
554 
557  create_status_message() const override
558  {
559  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
560  return std::shared_ptr<void>(new GoalStatusMessage());
561  }
562 
564  void
566  {
567  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
568  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
569  auto status_message = std::static_pointer_cast<GoalStatusMessage>(message);
570  for (const GoalStatus & status : status_message->status_list) {
571  const GoalUUID & goal_id = status.goal_info.goal_id.uuid;
572  if (goal_handles_.count(goal_id) == 0) {
573  RCLCPP_DEBUG(
574  this->get_logger(),
575  "Received status for unknown goal. Ignoring...");
576  continue;
577  }
578  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id];
579  goal_handle->set_status(status.status);
580  const int8_t goal_status = goal_handle->get_status();
581  if (
582  goal_status == GoalStatus::STATUS_SUCCEEDED ||
583  goal_status == GoalStatus::STATUS_CANCELED ||
584  goal_status == GoalStatus::STATUS_ABORTED)
585  {
586  goal_handles_.erase(goal_id);
587  }
588  }
589  }
590 
592  void
593  make_result_aware(typename GoalHandle::SharedPtr goal_handle)
594  {
595  // Avoid making more than one request
596  if (goal_handle->set_result_awareness(true)) {
597  return;
598  }
599  using GoalResultRequest = typename ActionT::Impl::GetResultService::Request;
600  auto goal_result_request = std::make_shared<GoalResultRequest>();
601  goal_result_request->goal_id.uuid = goal_handle->get_goal_id();
602  this->send_result_request(
603  std::static_pointer_cast<void>(goal_result_request),
604  [goal_handle, this](std::shared_ptr<void> response) mutable
605  {
606  // Wrap the response in a struct with the fields a user cares about
607  WrappedResult wrapped_result;
608  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
609  auto result_response = std::static_pointer_cast<GoalResultResponse>(response);
610  wrapped_result.result = std::make_shared<typename ActionT::Result>();
611  *wrapped_result.result = result_response->result;
612  wrapped_result.goal_id = goal_handle->get_goal_id();
613  wrapped_result.code = static_cast<ResultCode>(result_response->status);
614  goal_handle->set_result(wrapped_result);
615  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
616  goal_handles_.erase(goal_handle->get_goal_id());
617  });
618  }
619 
622  async_cancel(
623  typename CancelRequest::SharedPtr cancel_request,
624  CancelCallback cancel_callback = nullptr)
625  {
626  // Put promise in the heap to move it around.
627  auto promise = std::make_shared<std::promise<typename CancelResponse::SharedPtr>>();
628  std::shared_future<typename CancelResponse::SharedPtr> future(promise->get_future());
629  this->send_cancel_request(
630  std::static_pointer_cast<void>(cancel_request),
631  [cancel_callback, promise](std::shared_ptr<void> response) mutable
632  {
633  auto cancel_response = std::static_pointer_cast<CancelResponse>(response);
634  promise->set_value(cancel_response);
635  if (cancel_callback) {
636  cancel_callback(cancel_response);
637  }
638  });
639  return future;
640  }
641 
643  std::mutex goal_handles_mutex_;
644 };
645 } // namespace rclcpp_action
646 
647 #endif // RCLCPP_ACTION__CLIENT_HPP_
virtual RCLCPP_ACTION_PUBLIC void send_result_request(std::shared_ptr< void > request, ResponseCallback callback)
SendGoalOptions()
Definition: client.hpp:278
Definition: client.hpp:57
Options for sending a goal.
Definition: client.hpp:276
typename ActionT::Goal Goal
Definition: client.hpp:260
std::shared_future< typename CancelResponse::SharedPtr > async_cancel_goal(typename GoalHandle::SharedPtr goal_handle, CancelCallback cancel_callback=nullptr)
Asynchronously request a goal be canceled.
Definition: client.hpp:431
virtual ~Client()
Definition: client.hpp:492
typename GoalHandle::ResultCallback ResultCallback
Definition: client.hpp:267
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions() override
Action Client.
Definition: client.hpp:255
virtual RCLCPP_ACTION_PUBLIC GoalUUID generate_goal_id()
ResultCallback result_callback
Function called when the result for the goal is received.
Definition: client.hpp:300
std::shared_future< WrappedResult > async_get_result(typename GoalHandle::SharedPtr goal_handle, ResultCallback result_callback=nullptr)
Asynchronously get the result for an active goal.
Definition: client.hpp:401
GoalResponse
A response returned by an action server callback when a goal is requested.
Definition: server.hpp:43
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers() override
typename ActionT::Feedback Feedback
Definition: client.hpp:261
ResultCode
The possible statuses that an action goal can finish with.
Definition: client_goal_handle.hpp:35
typename GoalHandle::WrappedResult WrappedResult
Definition: client.hpp:263
CancelResponse
A response returned by an action server callback when a goal has been asked to be canceled...
Definition: server.hpp:54
T current_exception(T... args)
typename ActionT::Impl::CancelGoalService::Response CancelResponse
Definition: client.hpp:269
RCLCPP_ACTION_PUBLIC ClientBase(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &action_name, const rosidl_action_type_support_t *type_support, const rcl_action_client_options_t &options)
virtual std::shared_ptr< void > create_cancel_response() const =0
virtual RCLCPP_ACTION_PUBLIC void handle_result_response(const rmw_request_id_t &response_header, std::shared_ptr< void > result_response)
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override
virtual std::shared_ptr< void > create_result_response() const =0
virtual RCLCPP_ACTION_PUBLIC ~ClientBase()
virtual std::shared_ptr< void > create_status_message() const =0
#define RCLCPP_DEBUG(logger,...)
Client(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &action_name, const rcl_action_client_options_t client_options=rcl_action_client_get_default_options())
Construct an action client.
Definition: client.hpp:315
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients() override
std::shared_future< typename CancelResponse::SharedPtr > async_cancel_goals_before(const rclcpp::Time &stamp, CancelCallback cancel_callback=nullptr)
Asynchronously request all goals at or before a specified time be canceled.
Definition: client.hpp:478
virtual std::shared_ptr< void > create_goal_response() const =0
T static_pointer_cast(T... args)
std::shared_future< typename CancelResponse::SharedPtr > async_cancel_all_goals(CancelCallback cancel_callback=nullptr)
Asynchronously request for all goals to be canceled.
Definition: client.hpp:456
#define RCLCPP_ACTION_PUBLIC
Definition: visibility_control.hpp:50
typename GoalHandle::FeedbackCallback FeedbackCallback
Definition: client.hpp:266
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
virtual RCLCPP_ACTION_PUBLIC void handle_goal_response(const rmw_request_id_t &response_header, std::shared_ptr< void > goal_response)
action_msgs::msg::GoalStatus GoalStatus
Definition: types.hpp:33
GoalResponseCallback goal_response_callback
Function called when the goal is accepted or rejected.
Definition: client.hpp:294
typename ActionT::Impl::CancelGoalService::Request CancelRequest
Definition: client.hpp:268
action_msgs::msg::GoalInfo GoalInfo
Definition: types.hpp:34
RCL_ACTION_PUBLIC rcl_action_client_options_t rcl_action_client_get_default_options(void)
RCLCPP_ACTION_PUBLIC bool wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout)
Wait for action_server_is_ready() to become true, or until the given timeout is reached.
Definition: client.hpp:44
virtual RCLCPP_ACTION_PUBLIC void send_goal_request(std::shared_ptr< void > request, ResponseCallback callback)
bool wait_for_action_server(std::chrono::duration< RepT, RatioT > timeout=std::chrono::duration< RepT, RatioT >(-1))
Wait for action_server_is_ready() to become true, or until the given timeout is reached.
Definition: client.hpp:71
virtual void handle_status_message(std::shared_ptr< void > message)=0
virtual RCLCPP_ACTION_PUBLIC void send_cancel_request(std::shared_ptr< void > request, ResponseCallback callback)
RCLCPP_ACTION_PUBLIC bool is_ready(rcl_wait_set_t *wait_set) override
FeedbackCallback feedback_callback
Function called whenever feedback is received for the goal.
Definition: client.hpp:297
virtual std::shared_ptr< void > create_feedback_message() const =0
T fill(T... args)
Class for interacting with goals sent from action clients.
Definition: client_goal_handle.hpp:58
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions() override
virtual RCLCPP_ACTION_PUBLIC void handle_cancel_response(const rmw_request_id_t &response_header, std::shared_ptr< void > cancel_response)
virtual void handle_feedback_message(std::shared_ptr< void > message)=0
RCLCPP_ACTION_PUBLIC rclcpp::Logger get_logger()
RCLCPP_ACTION_PUBLIC void execute() override
RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t *wait_set) override
std::shared_future< typename GoalHandle::SharedPtr > async_send_goal(const Goal &goal, const SendGoalOptions &options=SendGoalOptions())
Send an action goal and asynchronously get the result.
Definition: client.hpp:343
RCLCPP_ACTION_PUBLIC bool action_server_is_ready() const
Return true if there is an action server that is ready to take goal requests.