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_runtime_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 
298 
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,
320  const rcl_action_client_options_t client_options = rcl_action_client_get_default_options()
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 
345  async_send_goal(const Goal & goal, const SendGoalOptions & options = SendGoalOptions())
346  {
347  // Put promise in the heap to move it around.
348  auto promise = std::make_shared<std::promise<typename GoalHandle::SharedPtr>>();
349  std::shared_future<typename GoalHandle::SharedPtr> future(promise->get_future());
350  using GoalRequest = typename ActionT::Impl::SendGoalService::Request;
351  auto goal_request = std::make_shared<GoalRequest>();
352  goal_request->goal_id.uuid = this->generate_goal_id();
353  goal_request->goal = goal;
354  this->send_goal_request(
355  std::static_pointer_cast<void>(goal_request),
356  [this, goal_request, options, promise, future](std::shared_ptr<void> response) mutable
357  {
358  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
359  auto goal_response = std::static_pointer_cast<GoalResponse>(response);
360  if (!goal_response->accepted) {
361  promise->set_value(nullptr);
362  if (options.goal_response_callback) {
363  options.goal_response_callback(future);
364  }
365  return;
366  }
367  GoalInfo goal_info;
368  goal_info.goal_id.uuid = goal_request->goal_id.uuid;
369  goal_info.stamp = goal_response->stamp;
370  // Do not use std::make_shared as friendship cannot be forwarded.
371  std::shared_ptr<GoalHandle> goal_handle(
372  new GoalHandle(goal_info, options.feedback_callback, options.result_callback));
373  {
374  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
375  goal_handles_[goal_handle->get_goal_id()] = goal_handle;
376  }
377  promise->set_value(goal_handle);
378  if (options.goal_response_callback) {
379  options.goal_response_callback(future);
380  }
381 
382  if (options.result_callback) {
383  try {
384  this->make_result_aware(goal_handle);
385  } catch (...) {
386  promise->set_exception(std::current_exception());
387  return;
388  }
389  }
390  });
391 
392  // TODO(jacobperron): Encapsulate into it's own function and
393  // consider exposing an option to disable this cleanup
394  // To prevent the list from growing out of control, forget about any goals
395  // with no more user references
396  {
397  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
398  auto goal_handle_it = goal_handles_.begin();
399  while (goal_handle_it != goal_handles_.end()) {
400  if (!goal_handle_it->second.lock()) {
401  RCLCPP_DEBUG(
402  this->get_logger(),
403  "Dropping weak reference to goal handle during send_goal()");
404  goal_handle_it = goal_handles_.erase(goal_handle_it);
405  } else {
406  ++goal_handle_it;
407  }
408  }
409  }
410 
411  return future;
412  }
413 
415 
424  typename GoalHandle::SharedPtr goal_handle,
425  ResultCallback result_callback = nullptr)
426  {
427  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
428  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
430  }
431  if (result_callback) {
432  // This will override any previously registered callback
433  goal_handle->set_result_callback(result_callback);
434  }
435  this->make_result_aware(goal_handle);
436  return goal_handle->async_get_result();
437  }
438 
440 
454  typename GoalHandle::SharedPtr goal_handle,
455  CancelCallback cancel_callback = nullptr)
456  {
457  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
458  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
460  }
461  auto cancel_request = std::make_shared<CancelRequest>();
462  // cancel_request->goal_info.goal_id = goal_handle->get_goal_id();
463  cancel_request->goal_info.goal_id.uuid = goal_handle->get_goal_id();
464  return async_cancel(cancel_request, cancel_callback);
465  }
466 
468 
478  async_cancel_all_goals(CancelCallback cancel_callback = nullptr)
479  {
480  auto cancel_request = std::make_shared<CancelRequest>();
481  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
482  std::fill(
483  cancel_request->goal_info.goal_id.uuid.begin(),
484  cancel_request->goal_info.goal_id.uuid.end(), 0u);
485  return async_cancel(cancel_request, cancel_callback);
486  }
487 
489 
501  const rclcpp::Time & stamp,
502  CancelCallback cancel_callback = nullptr)
503  {
504  auto cancel_request = std::make_shared<CancelRequest>();
505  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
506  std::fill(
507  cancel_request->goal_info.goal_id.uuid.begin(),
508  cancel_request->goal_info.goal_id.uuid.end(), 0u);
509  cancel_request->goal_info.stamp = stamp;
510  return async_cancel(cancel_request, cancel_callback);
511  }
512 
513  virtual
515  {
516  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
517  auto it = goal_handles_.begin();
518  while (it != goal_handles_.end()) {
519  typename GoalHandle::SharedPtr goal_handle = it->second.lock();
520  if (goal_handle) {
521  goal_handle->invalidate();
522  }
523  it = goal_handles_.erase(it);
524  }
525  }
526 
527 private:
530  create_goal_response() const override
531  {
532  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
533  return std::shared_ptr<void>(new GoalResponse());
534  }
535 
538  create_result_response() const override
539  {
540  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
541  return std::shared_ptr<void>(new GoalResultResponse());
542  }
543 
546  create_cancel_response() const override
547  {
549  }
550 
553  create_feedback_message() const override
554  {
555  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
556  return std::shared_ptr<void>(new FeedbackMessage());
557  }
558 
560  void
561  handle_feedback_message(std::shared_ptr<void> message) override
562  {
563  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
564  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
565  typename FeedbackMessage::SharedPtr feedback_message =
566  std::static_pointer_cast<FeedbackMessage>(message);
567  const GoalUUID & goal_id = feedback_message->goal_id.uuid;
568  if (goal_handles_.count(goal_id) == 0) {
569  RCLCPP_DEBUG(
570  this->get_logger(),
571  "Received feedback for unknown goal. Ignoring...");
572  return;
573  }
574  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
575  // Forget about the goal if there are no more user references
576  if (!goal_handle) {
577  RCLCPP_DEBUG(
578  this->get_logger(),
579  "Dropping weak reference to goal handle during feedback callback");
580  goal_handles_.erase(goal_id);
581  return;
582  }
583  auto feedback = std::make_shared<Feedback>();
584  *feedback = feedback_message->feedback;
585  goal_handle->call_feedback_callback(goal_handle, feedback);
586  }
587 
590  create_status_message() const override
591  {
592  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
593  return std::shared_ptr<void>(new GoalStatusMessage());
594  }
595 
597  void
598  handle_status_message(std::shared_ptr<void> message) override
599  {
600  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
601  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
602  auto status_message = std::static_pointer_cast<GoalStatusMessage>(message);
603  for (const GoalStatus & status : status_message->status_list) {
604  const GoalUUID & goal_id = status.goal_info.goal_id.uuid;
605  if (goal_handles_.count(goal_id) == 0) {
606  RCLCPP_DEBUG(
607  this->get_logger(),
608  "Received status for unknown goal. Ignoring...");
609  continue;
610  }
611  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
612  // Forget about the goal if there are no more user references
613  if (!goal_handle) {
614  RCLCPP_DEBUG(
615  this->get_logger(),
616  "Dropping weak reference to goal handle during status callback");
617  goal_handles_.erase(goal_id);
618  continue;
619  }
620  goal_handle->set_status(status.status);
621  }
622  }
623 
625  void
626  make_result_aware(typename GoalHandle::SharedPtr goal_handle)
627  {
628  // Avoid making more than one request
629  if (goal_handle->set_result_awareness(true)) {
630  return;
631  }
632  using GoalResultRequest = typename ActionT::Impl::GetResultService::Request;
633  auto goal_result_request = std::make_shared<GoalResultRequest>();
634  goal_result_request->goal_id.uuid = goal_handle->get_goal_id();
635  this->send_result_request(
636  std::static_pointer_cast<void>(goal_result_request),
637  [goal_handle, this](std::shared_ptr<void> response) mutable
638  {
639  // Wrap the response in a struct with the fields a user cares about
640  WrappedResult wrapped_result;
641  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
642  auto result_response = std::static_pointer_cast<GoalResultResponse>(response);
643  wrapped_result.result = std::make_shared<typename ActionT::Result>();
644  *wrapped_result.result = result_response->result;
645  wrapped_result.goal_id = goal_handle->get_goal_id();
646  wrapped_result.code = static_cast<ResultCode>(result_response->status);
647  goal_handle->set_result(wrapped_result);
648  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
649  goal_handles_.erase(goal_handle->get_goal_id());
650  });
651  }
652 
655  async_cancel(
656  typename CancelRequest::SharedPtr cancel_request,
657  CancelCallback cancel_callback = nullptr)
658  {
659  // Put promise in the heap to move it around.
660  auto promise = std::make_shared<std::promise<typename CancelResponse::SharedPtr>>();
661  std::shared_future<typename CancelResponse::SharedPtr> future(promise->get_future());
662  this->send_cancel_request(
663  std::static_pointer_cast<void>(cancel_request),
664  [cancel_callback, promise](std::shared_ptr<void> response) mutable
665  {
666  auto cancel_response = std::static_pointer_cast<CancelResponse>(response);
667  promise->set_value(cancel_response);
668  if (cancel_callback) {
669  cancel_callback(cancel_response);
670  }
671  });
672  return future;
673  }
674 
676  std::mutex goal_handles_mutex_;
677 };
678 } // namespace rclcpp_action
679 
680 #endif // RCLCPP_ACTION__CLIENT_HPP_
node_logging_interface.hpp
std::shared_future
std::lock
T lock(T... args)
rclcpp_action::GoalResponse
GoalResponse
A response returned by an action server callback when a goal is requested.
Definition: server.hpp:43
rclcpp_action::ClientBase::get_number_of_ready_clients
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_clients() override
rclcpp_action::ClientBase::create_result_response
virtual std::shared_ptr< void > create_result_response() const =0
std::string
std::shared_ptr< void >
rclcpp_action::Client::async_send_goal
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:345
rclcpp_action::ClientBase::handle_goal_response
virtual RCLCPP_ACTION_PUBLIC void handle_goal_response(const rmw_request_id_t &response_header, std::shared_ptr< void > goal_response)
rclcpp_action::ClientGoalHandle
Class for interacting with goals sent from action clients.
Definition: client_goal_handle.hpp:58
rclcpp_action::Client::CancelRequest
typename ActionT::Impl::CancelGoalService::Request CancelRequest
Definition: client.hpp:268
rclcpp_action::ClientBase::wait_for_action_server_nanoseconds
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.
node_graph_interface.hpp
types.hpp
std::chrono::duration
rclcpp_action::Client::GoalHandle
ClientGoalHandle< ActionT > GoalHandle
Definition: client.hpp:262
rclcpp::Time
std::lock_guard
node_base_interface.hpp
rclcpp_action::ClientBase::send_goal_request
virtual RCLCPP_ACTION_PUBLIC void send_goal_request(std::shared_ptr< void > request, ResponseCallback callback)
rclcpp_action::Client::WrappedResult
typename GoalHandle::WrappedResult WrappedResult
Definition: client.hpp:263
rclcpp_action::GoalUUID
std::array< uint8_t, UUID_SIZE > GoalUUID
Definition: types.hpp:32
std::function
rclcpp_action::ClientBase::wait_for_action_server
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
rclcpp::Waitable
rclcpp_action::Client::Goal
typename ActionT::Goal Goal
Definition: client.hpp:260
rclcpp_action
Definition: client.hpp:44
rclcpp_action::ClientBase::is_ready
RCLCPP_ACTION_PUBLIC bool is_ready(rcl_wait_set_t *wait_set) override
rclcpp_action::Client::SendGoalOptions::feedback_callback
FeedbackCallback feedback_callback
Function called whenever feedback is received for the goal.
Definition: client.hpp:297
std::current_exception
T current_exception(T... args)
std::fill
T fill(T... args)
rclcpp_action::ClientBase::get_logger
RCLCPP_ACTION_PUBLIC rclcpp::Logger get_logger()
logger.hpp
rclcpp_action::ClientBase::handle_status_message
virtual void handle_status_message(std::shared_ptr< void > message)=0
rclcpp_action::ClientBase::handle_cancel_response
virtual RCLCPP_ACTION_PUBLIC void handle_cancel_response(const rmw_request_id_t &response_header, std::shared_ptr< void > cancel_response)
rclcpp_action::ClientBase::get_number_of_ready_subscriptions
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_subscriptions() override
rclcpp_action::Client::async_cancel_all_goals
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:478
rclcpp_action::Client::CancelCallback
std::function< void(typename CancelResponse::SharedPtr)> CancelCallback
Definition: client.hpp:270
rclcpp_action::ClientBase::send_cancel_request
virtual RCLCPP_ACTION_PUBLIC void send_cancel_request(std::shared_ptr< void > request, ResponseCallback callback)
rclcpp_action::exceptions::UnknownGoalHandleError
Definition: exceptions.hpp:24
rclcpp_action::Client::Feedback
typename ActionT::Feedback Feedback
Definition: client.hpp:261
rclcpp_action::Client::async_cancel_goal
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:453
rclcpp_action::ClientBase::create_feedback_message
virtual std::shared_ptr< void > create_feedback_message() const =0
rclcpp_action::ClientBase::handle_feedback_message
virtual void handle_feedback_message(std::shared_ptr< void > message)=0
rclcpp_action::Client::FeedbackCallback
typename GoalHandle::FeedbackCallback FeedbackCallback
Definition: client.hpp:266
rclcpp_action::ClientBase::add_to_wait_set
RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t *wait_set) override
rclcpp_action::ClientBase::execute
RCLCPP_ACTION_PUBLIC void execute() override
rclcpp_action::GoalStatus
action_msgs::msg::GoalStatus GoalStatus
Definition: types.hpp:33
rclcpp::Logger
waitable.hpp
rclcpp_action::ClientBase::send_result_request
virtual RCLCPP_ACTION_PUBLIC void send_result_request(std::shared_ptr< void > request, ResponseCallback callback)
std::array
rmw_request_id_t
rcl_wait_set_t
rclcpp_action::ClientBase::get_number_of_ready_guard_conditions
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_guard_conditions() override
RCLCPP_DEBUG
#define RCLCPP_DEBUG(logger,...)
rclcpp_action::Client::SendGoalOptions::SendGoalOptions
SendGoalOptions()
Definition: client.hpp:278
std::map
rclcpp_action::ClientBase::action_server_is_ready
RCLCPP_ACTION_PUBLIC bool action_server_is_ready() const
Return true if there is an action server that is ready to take goal requests.
rclcpp_action::GoalInfo
action_msgs::msg::GoalInfo GoalInfo
Definition: types.hpp:34
rcl_action_client_options_t
rclcpp_action::Client::ResultCallback
typename GoalHandle::ResultCallback ResultCallback
Definition: client.hpp:267
rclcpp_action::ClientBase::generate_goal_id
virtual RCLCPP_ACTION_PUBLIC GoalUUID generate_goal_id()
rclcpp_action::Client::SendGoalOptions
Options for sending a goal.
Definition: client.hpp:276
rclcpp_action::Client::Client
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
visibility_control.hpp
rclcpp_action::ClientBase::get_number_of_ready_timers
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_timers() override
std
rclcpp_action::Client::async_cancel_goals_before
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:500
rclcpp_action::ClientBase
Definition: client.hpp:57
RCLCPP_ACTION_PUBLIC
#define RCLCPP_ACTION_PUBLIC
Definition: visibility_control.hpp:50
rclcpp_action::Client::SendGoalOptions::result_callback
ResultCallback result_callback
Function called when the result for the goal is received.
Definition: client.hpp:300
rclcpp_action::ClientBase::ClientBase
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)
rclcpp_action::Client::async_get_result
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:423
time.hpp
rclcpp_action::Client::SendGoalOptions::goal_response_callback
GoalResponseCallback goal_response_callback
Function called when the goal is accepted or rejected.
Definition: client.hpp:294
rclcpp_action::ClientBase::create_cancel_response
virtual std::shared_ptr< void > create_cancel_response() const =0
std::mutex
RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE
#define RCLCPP_SMART_PTR_DEFINITIONS_NOT_COPYABLE(...)
rclcpp_action::Client::CancelResponse
typename ActionT::Impl::CancelGoalService::Response CancelResponse
Definition: client.hpp:269
client_goal_handle.hpp
std::unique_ptr< ClientBaseImpl >
rclcpp_action::ResultCode
ResultCode
The possible statuses that an action goal can finish with.
Definition: client_goal_handle.hpp:35
macros.hpp
rclcpp_action::Client
Action Client.
Definition: client.hpp:255
rclcpp_action::ClientBase::handle_result_response
virtual RCLCPP_ACTION_PUBLIC void handle_result_response(const rmw_request_id_t &response_header, std::shared_ptr< void > result_response)
rclcpp_action::Client::~Client
virtual ~Client()
Definition: client.hpp:514
rclcpp_action::ClientBase::get_number_of_ready_services
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override
rclcpp_action::ClientBase::create_goal_response
virtual std::shared_ptr< void > create_goal_response() const =0
rclcpp_action::ClientBase::~ClientBase
virtual RCLCPP_ACTION_PUBLIC ~ClientBase()
rclcpp_action::ClientBase::create_status_message
virtual std::shared_ptr< void > create_status_message() const =0