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/exceptions.hpp>
19 #include <rclcpp/macros.hpp>
23 #include <rclcpp/logger.hpp>
24 #include <rclcpp/time.hpp>
25 #include <rclcpp/waitable.hpp>
26 
27 #include <rosidl_runtime_c/action_type_support_struct.h>
28 #include <rosidl_typesupport_cpp/action_type_support.hpp>
29 
30 #include <algorithm>
31 #include <chrono>
32 #include <functional>
33 #include <future>
34 #include <map>
35 #include <memory>
36 #include <mutex>
37 #include <string>
38 #include <utility>
39 
42 #include "rclcpp_action/types.hpp"
44 
45 
46 namespace rclcpp_action
47 {
48 // Forward declaration
49 class ClientBaseImpl;
50 
53 
60 {
61 public:
63  virtual ~ClientBase();
64 
67  bool
68  action_server_is_ready() const;
69 
71  template<typename RepT = int64_t, typename RatioT = std::milli>
72  bool
75  {
77  std::chrono::duration_cast<std::chrono::nanoseconds>(timeout)
78  );
79  }
80 
81  // -------------
82  // Waitables API
83 
86  size_t
88 
91  size_t
92  get_number_of_ready_timers() override;
93 
96  size_t
97  get_number_of_ready_clients() override;
98 
101  size_t
102  get_number_of_ready_services() override;
103 
106  size_t
108 
111  bool
112  add_to_wait_set(rcl_wait_set_t * wait_set) override;
113 
116  bool
117  is_ready(rcl_wait_set_t * wait_set) override;
118 
122  take_data() override;
123 
126  void
127  execute(std::shared_ptr<void> & data) override;
128 
129  // End Waitables API
130  // -----------------
131 
132 protected:
134  ClientBase(
135  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
136  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
137  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
138  const std::string & action_name,
139  const rosidl_action_type_support_t * type_support,
140  const rcl_action_client_options_t & options);
141 
144  bool
146 
147  // -----------------------------------------------------
148  // API for communication between ClientBase and Client<>
150 
154 
157  virtual
158  GoalUUID
160 
163  virtual
164  void
166  std::shared_ptr<void> request,
167  ResponseCallback callback);
168 
171  virtual
172  void
174  std::shared_ptr<void> request,
175  ResponseCallback callback);
176 
179  virtual
180  void
182  std::shared_ptr<void> request,
183  ResponseCallback callback);
184 
186  virtual
188  create_goal_response() const = 0;
189 
192  virtual
193  void
195  const rmw_request_id_t & response_header,
196  std::shared_ptr<void> goal_response);
197 
199  virtual
201  create_result_response() const = 0;
202 
205  virtual
206  void
208  const rmw_request_id_t & response_header,
209  std::shared_ptr<void> result_response);
210 
212  virtual
214  create_cancel_response() const = 0;
215 
218  virtual
219  void
221  const rmw_request_id_t & response_header,
222  std::shared_ptr<void> cancel_response);
223 
225  virtual
227  create_feedback_message() const = 0;
228 
230  virtual
231  void
233 
235  virtual
237  create_status_message() const = 0;
238 
240  virtual
241  void
243 
244  // End API for communication between ClientBase and Client<>
245  // ---------------------------------------------------------
246 
247 private:
249 };
250 
252 
261 template<typename ActionT>
262 class Client : public ClientBase
263 {
264 public:
266 
267  using Goal = typename ActionT::Goal;
268  using Feedback = typename ActionT::Feedback;
269  using GoalHandle = ClientGoalHandle<ActionT>;
273  using CancelRequest = typename ActionT::Impl::CancelGoalService::Request;
274  using CancelResponse = typename ActionT::Impl::CancelGoalService::Response;
275  using CancelCallback = std::function<void (typename CancelResponse::SharedPtr)>;
276 
279  {
280 public:
281  using NewSignature = std::function<void (typename GoalHandle::SharedPtr)>;
283 
284  GoalResponseCallback() = default;
285 
286  GoalResponseCallback(std::nullptr_t) {} // NOLINT, intentionally implicit.
287 
288  // implicit constructor
289  [[deprecated(
290  "Use new goal response callback signature "
291  "`std::function<void (Client<ActionT>::GoalHandle::SharedPtr)>` "
292  "instead of the old "
293  "`std::function<void (std::shared_future<Client<ActionT>::GoalHandle::SharedPtr>)>`.\n"
294  "e.g.:\n"
295  "```cpp\n"
296  "Client<ActionT>::SendGoalOptions options;\n"
297  "options.goal_response_callback = [](Client<ActionT>::GoalHandle::SharedPtr goal) {\n"
298  " // do something with `goal` here\n"
299  "};")]]
300  GoalResponseCallback(OldSignature old_callback) // NOLINT, intentionally implicit.
301  : old_callback_(std::move(old_callback)) {}
302 
303  GoalResponseCallback(NewSignature new_callback) // NOLINT, intentionally implicit.
304  : new_callback_(std::move(new_callback)) {}
305 
307  operator=(OldSignature old_callback) {old_callback_ = std::move(old_callback); return *this;}
308 
310  operator=(NewSignature new_callback) {new_callback_ = std::move(new_callback); return *this;}
311 
312  void
313  operator()(typename GoalHandle::SharedPtr goal_handle) const
314  {
315  if (new_callback_) {
316  new_callback_(std::move(goal_handle));
317  return;
318  }
319  if (old_callback_) {
320  throw std::runtime_error{
321  "Cannot call GoalResponseCallback(GoalHandle::SharedPtr) "
322  "if using the old goal response callback signature."};
323  }
324  throw std::bad_function_call{};
325  }
326 
327  [[deprecated(
328  "Calling "
329  "`void goal_response_callback("
330  " std::shared_future<Client<ActionT>::GoalHandle::SharedPtr> goal_handle_shared_future)`"
331  " is deprecated.")]]
332  void
334  {
335  if (old_callback_) {
336  old_callback_(std::move(goal_handle_future));
337  return;
338  }
339  if (new_callback_) {
340  new_callback_(std::move(goal_handle_future).get_future().share());
341  return;
342  }
343  throw std::bad_function_call{};
344  }
345 
346  explicit operator bool() const noexcept {
347  return new_callback_ || old_callback_;
348  }
349 
350 private:
351  friend class Client;
352  void
353  operator()(
354  typename GoalHandle::SharedPtr goal_handle,
356  {
357  if (new_callback_) {
358  new_callback_(std::move(goal_handle));
359  return;
360  }
361  if (old_callback_) {
362  old_callback_(std::move(goal_handle_future));
363  return;
364  }
365  throw std::bad_function_call{};
366  }
367 
368  NewSignature new_callback_;
369  OldSignature old_callback_;
370  };
371 
373 
377  {
379  : goal_response_callback(nullptr),
380  feedback_callback(nullptr),
381  result_callback(nullptr)
382  {
383  }
384 
386 
392 
395 
398  };
399 
401 
413  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
414  rclcpp::node_interfaces::NodeGraphInterface::SharedPtr node_graph,
415  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
416  const std::string & action_name,
417  const rcl_action_client_options_t & client_options = rcl_action_client_get_default_options()
418  )
419  : ClientBase(
420  node_base, node_graph, node_logging, action_name,
421  rosidl_typesupport_cpp::get_action_type_support_handle<ActionT>(),
422  client_options)
423  {
424  }
425 
427 
442  async_send_goal(const Goal & goal, const SendGoalOptions & options = SendGoalOptions())
443  {
444  // Put promise in the heap to move it around.
445  auto promise = std::make_shared<std::promise<typename GoalHandle::SharedPtr>>();
446  std::shared_future<typename GoalHandle::SharedPtr> future(promise->get_future());
447  using GoalRequest = typename ActionT::Impl::SendGoalService::Request;
448  auto goal_request = std::make_shared<GoalRequest>();
449  goal_request->goal_id.uuid = this->generate_goal_id();
450  goal_request->goal = goal;
451  this->send_goal_request(
452  std::static_pointer_cast<void>(goal_request),
453  [this, goal_request, options, promise, future](std::shared_ptr<void> response) mutable
454  {
455  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
456  auto goal_response = std::static_pointer_cast<GoalResponse>(response);
457  if (!goal_response->accepted) {
458  promise->set_value(nullptr);
459  if (options.goal_response_callback) {
460  options.goal_response_callback(nullptr, future);
461  }
462  return;
463  }
464  GoalInfo goal_info;
465  goal_info.goal_id.uuid = goal_request->goal_id.uuid;
466  goal_info.stamp = goal_response->stamp;
467  // Do not use std::make_shared as friendship cannot be forwarded.
468  std::shared_ptr<GoalHandle> goal_handle(
469  new GoalHandle(goal_info, options.feedback_callback, options.result_callback));
470  {
471  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
472  goal_handles_[goal_handle->get_goal_id()] = goal_handle;
473  }
474  promise->set_value(goal_handle);
475  if (options.goal_response_callback) {
476  options.goal_response_callback(goal_handle, future);
477  }
478 
479  if (options.result_callback) {
480  this->make_result_aware(goal_handle);
481  }
482  });
483 
484  // TODO(jacobperron): Encapsulate into it's own function and
485  // consider exposing an option to disable this cleanup
486  // To prevent the list from growing out of control, forget about any goals
487  // with no more user references
488  {
489  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
490  auto goal_handle_it = goal_handles_.begin();
491  while (goal_handle_it != goal_handles_.end()) {
492  if (!goal_handle_it->second.lock()) {
493  RCLCPP_DEBUG(
494  this->get_logger(),
495  "Dropping weak reference to goal handle during send_goal()");
496  goal_handle_it = goal_handles_.erase(goal_handle_it);
497  } else {
498  ++goal_handle_it;
499  }
500  }
501  }
502 
503  return future;
504  }
505 
507 
516  typename GoalHandle::SharedPtr goal_handle,
517  ResultCallback result_callback = nullptr)
518  {
519  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
520  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
522  }
523  if (goal_handle->is_invalidated()) {
524  // This case can happen if there was a failure to send the result request
525  // during the goal response callback
526  throw goal_handle->invalidate_exception_;
527  }
528  if (result_callback) {
529  // This will override any previously registered callback
530  goal_handle->set_result_callback(result_callback);
531  }
532  this->make_result_aware(goal_handle);
533  return goal_handle->async_get_result();
534  }
535 
537 
551  typename GoalHandle::SharedPtr goal_handle,
552  CancelCallback cancel_callback = nullptr)
553  {
554  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
555  if (goal_handles_.count(goal_handle->get_goal_id()) == 0) {
557  }
558  auto cancel_request = std::make_shared<CancelRequest>();
559  // cancel_request->goal_info.goal_id = goal_handle->get_goal_id();
560  cancel_request->goal_info.goal_id.uuid = goal_handle->get_goal_id();
561  return async_cancel(cancel_request, cancel_callback);
562  }
563 
565 
575  async_cancel_all_goals(CancelCallback cancel_callback = nullptr)
576  {
577  auto cancel_request = std::make_shared<CancelRequest>();
578  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
579  std::fill(
580  cancel_request->goal_info.goal_id.uuid.begin(),
581  cancel_request->goal_info.goal_id.uuid.end(), 0u);
582  return async_cancel(cancel_request, cancel_callback);
583  }
584 
586 
598  const rclcpp::Time & stamp,
599  CancelCallback cancel_callback = nullptr)
600  {
601  auto cancel_request = std::make_shared<CancelRequest>();
602  // std::fill(cancel_request->goal_info.goal_id.uuid, 0u);
603  std::fill(
604  cancel_request->goal_info.goal_id.uuid.begin(),
605  cancel_request->goal_info.goal_id.uuid.end(), 0u);
606  cancel_request->goal_info.stamp = stamp;
607  return async_cancel(cancel_request, cancel_callback);
608  }
609 
610  virtual
612  {
613  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
614  auto it = goal_handles_.begin();
615  while (it != goal_handles_.end()) {
616  typename GoalHandle::SharedPtr goal_handle = it->second.lock();
617  if (goal_handle) {
618  goal_handle->invalidate(exceptions::UnawareGoalHandleError());
619  }
620  it = goal_handles_.erase(it);
621  }
622  }
623 
624 private:
627  create_goal_response() const override
628  {
629  using GoalResponse = typename ActionT::Impl::SendGoalService::Response;
630  return std::shared_ptr<void>(new GoalResponse());
631  }
632 
635  create_result_response() const override
636  {
637  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
638  return std::shared_ptr<void>(new GoalResultResponse());
639  }
640 
643  create_cancel_response() const override
644  {
646  }
647 
650  create_feedback_message() const override
651  {
652  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
653  return std::shared_ptr<void>(new FeedbackMessage());
654  }
655 
657  void
658  handle_feedback_message(std::shared_ptr<void> message) override
659  {
660  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
661  using FeedbackMessage = typename ActionT::Impl::FeedbackMessage;
662  typename FeedbackMessage::SharedPtr feedback_message =
663  std::static_pointer_cast<FeedbackMessage>(message);
664  const GoalUUID & goal_id = feedback_message->goal_id.uuid;
665  if (goal_handles_.count(goal_id) == 0) {
666  RCLCPP_DEBUG(
667  this->get_logger(),
668  "Received feedback for unknown goal. Ignoring...");
669  return;
670  }
671  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
672  // Forget about the goal if there are no more user references
673  if (!goal_handle) {
674  RCLCPP_DEBUG(
675  this->get_logger(),
676  "Dropping weak reference to goal handle during feedback callback");
677  goal_handles_.erase(goal_id);
678  return;
679  }
680  auto feedback = std::make_shared<Feedback>();
681  *feedback = feedback_message->feedback;
682  goal_handle->call_feedback_callback(goal_handle, feedback);
683  }
684 
687  create_status_message() const override
688  {
689  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
690  return std::shared_ptr<void>(new GoalStatusMessage());
691  }
692 
694  void
695  handle_status_message(std::shared_ptr<void> message) override
696  {
697  std::lock_guard<std::mutex> guard(goal_handles_mutex_);
698  using GoalStatusMessage = typename ActionT::Impl::GoalStatusMessage;
699  auto status_message = std::static_pointer_cast<GoalStatusMessage>(message);
700  for (const GoalStatus & status : status_message->status_list) {
701  const GoalUUID & goal_id = status.goal_info.goal_id.uuid;
702  if (goal_handles_.count(goal_id) == 0) {
703  RCLCPP_DEBUG(
704  this->get_logger(),
705  "Received status for unknown goal. Ignoring...");
706  continue;
707  }
708  typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
709  // Forget about the goal if there are no more user references
710  if (!goal_handle) {
711  RCLCPP_DEBUG(
712  this->get_logger(),
713  "Dropping weak reference to goal handle during status callback");
714  goal_handles_.erase(goal_id);
715  continue;
716  }
717  goal_handle->set_status(status.status);
718  }
719  }
720 
722  void
723  make_result_aware(typename GoalHandle::SharedPtr goal_handle)
724  {
725  // Avoid making more than one request
726  if (goal_handle->set_result_awareness(true)) {
727  return;
728  }
729  using GoalResultRequest = typename ActionT::Impl::GetResultService::Request;
730  auto goal_result_request = std::make_shared<GoalResultRequest>();
731  goal_result_request->goal_id.uuid = goal_handle->get_goal_id();
732  try {
733  this->send_result_request(
734  std::static_pointer_cast<void>(goal_result_request),
735  [goal_handle, this](std::shared_ptr<void> response) mutable
736  {
737  // Wrap the response in a struct with the fields a user cares about
738  WrappedResult wrapped_result;
739  using GoalResultResponse = typename ActionT::Impl::GetResultService::Response;
740  auto result_response = std::static_pointer_cast<GoalResultResponse>(response);
741  wrapped_result.result = std::make_shared<typename ActionT::Result>();
742  *wrapped_result.result = result_response->result;
743  wrapped_result.goal_id = goal_handle->get_goal_id();
744  wrapped_result.code = static_cast<ResultCode>(result_response->status);
745  goal_handle->set_result(wrapped_result);
746  std::lock_guard<std::mutex> lock(goal_handles_mutex_);
747  goal_handles_.erase(goal_handle->get_goal_id());
748  });
749  } catch (rclcpp::exceptions::RCLError & ex) {
750  // This will cause an exception when the user tries to access the result
751  goal_handle->invalidate(exceptions::UnawareGoalHandleError(ex.message));
752  }
753  }
754 
757  async_cancel(
758  typename CancelRequest::SharedPtr cancel_request,
759  CancelCallback cancel_callback = nullptr)
760  {
761  // Put promise in the heap to move it around.
762  auto promise = std::make_shared<std::promise<typename CancelResponse::SharedPtr>>();
763  std::shared_future<typename CancelResponse::SharedPtr> future(promise->get_future());
764  this->send_cancel_request(
765  std::static_pointer_cast<void>(cancel_request),
766  [cancel_callback, promise](std::shared_ptr<void> response) mutable
767  {
768  auto cancel_response = std::static_pointer_cast<CancelResponse>(response);
769  promise->set_value(cancel_response);
770  if (cancel_callback) {
771  cancel_callback(cancel_response);
772  }
773  });
774  return future;
775  }
776 
778  std::mutex goal_handles_mutex_;
779 };
780 } // namespace rclcpp_action
781 
782 #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
exceptions.hpp
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:442
std::move
T move(T... args)
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:59
rclcpp::exceptions::RCLError
rclcpp_action::Client::CancelRequest
typename ActionT::Impl::CancelGoalService::Request CancelRequest
Definition: client.hpp:273
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:269
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:270
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:73
rclcpp::Waitable
rclcpp_action::Client::Goal
typename ActionT::Goal Goal
Definition: client.hpp:267
rclcpp_action
Definition: client.hpp:46
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:394
std::fill
T fill(T... args)
rclcpp_action::ClientBase::get_logger
RCLCPP_ACTION_PUBLIC rclcpp::Logger get_logger()
logger.hpp
rclcpp_action::Client::GoalResponseCallback::GoalResponseCallback
GoalResponseCallback(OldSignature old_callback)
Definition: client.hpp:300
rclcpp_action::ClientBase::execute
RCLCPP_ACTION_PUBLIC void execute(std::shared_ptr< void > &data) override
rclcpp_action::ClientBase::handle_status_message
virtual void handle_status_message(std::shared_ptr< void > message)=0
std::nullptr_t
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:575
rclcpp_action::Client::CancelCallback
std::function< void(typename CancelResponse::SharedPtr)> CancelCallback
Definition: client.hpp:275
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:25
rclcpp_action::Client::Feedback
typename ActionT::Feedback Feedback
Definition: client.hpp:268
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:550
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:271
rclcpp_action::ClientBase::add_to_wait_set
RCLCPP_ACTION_PUBLIC bool add_to_wait_set(rcl_wait_set_t *wait_set) override
rclcpp_action::GoalStatus
action_msgs::msg::GoalStatus GoalStatus
Definition: types.hpp:33
rclcpp::Logger
waitable.hpp
rclcpp_action::exceptions::UnawareGoalHandleError
Definition: exceptions.hpp:34
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
rclcpp::exceptions::RCLErrorBase::message
std::string message
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,...)
std::runtime_error
rclcpp_action::Client::SendGoalOptions::SendGoalOptions
SendGoalOptions()
Definition: client.hpp:378
std::bad_function_call
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:272
rclcpp_action::ClientBase::generate_goal_id
virtual RCLCPP_ACTION_PUBLIC GoalUUID generate_goal_id()
rclcpp_action::Client::GoalResponseCallback
Compatibility wrapper for goal_response_callback.
Definition: client.hpp:278
rclcpp_action::Client::SendGoalOptions
Options for sending a goal.
Definition: client.hpp:376
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:412
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:597
rclcpp_action::Client::GoalResponseCallback::operator=
GoalResponseCallback & operator=(OldSignature old_callback)
Definition: client.hpp:307
rclcpp_action::ClientBase
Definition: client.hpp:59
RCLCPP_ACTION_PUBLIC
#define RCLCPP_ACTION_PUBLIC
Definition: visibility_control.hpp:50
rclcpp_action::Client::GoalResponseCallback::GoalResponseCallback
GoalResponseCallback(NewSignature new_callback)
Definition: client.hpp:303
rclcpp_action::Client::SendGoalOptions::result_callback
ResultCallback result_callback
Function called when the result for the goal is received.
Definition: client.hpp:397
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:515
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:391
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::GoalResponseCallback::operator=
GoalResponseCallback & operator=(NewSignature new_callback)
Definition: client.hpp:310
rclcpp_action::Client::CancelResponse
typename ActionT::Impl::CancelGoalService::Response CancelResponse
Definition: client.hpp:274
rclcpp_action::Client::GoalResponseCallback::operator()
void operator()(std::shared_future< typename GoalHandle::SharedPtr > goal_handle_future) const
Definition: client.hpp:333
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:36
rclcpp_action::Client::GoalResponseCallback::GoalResponseCallback
GoalResponseCallback(std::nullptr_t)
Definition: client.hpp:286
macros.hpp
rclcpp_action::Client::GoalResponseCallback::operator()
void operator()(typename GoalHandle::SharedPtr goal_handle) const
Definition: client.hpp:313
rclcpp_action::Client
Action Client.
Definition: client.hpp:262
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:611
rclcpp_action::ClientBase::get_number_of_ready_services
RCLCPP_ACTION_PUBLIC size_t get_number_of_ready_services() override
exceptions.hpp
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
rclcpp_action::ClientBase::take_data
RCLCPP_ACTION_PUBLIC std::shared_ptr< void > take_data() override