Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
simple_action_server.hpp
1 // Copyright (c) 2019 Intel Corporation
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 NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
16 #define NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
17 
18 #include <memory>
19 #include <mutex>
20 #include <string>
21 #include <thread>
22 #include <future>
23 #include <chrono>
24 
25 #include "rclcpp/rclcpp.hpp"
26 #include "rclcpp_action/rclcpp_action.hpp"
27 #include "nav2_util/node_thread.hpp"
28 
29 namespace nav2_util
30 {
31 
36 template<typename ActionT>
38 {
39 public:
40  // Callback function to complete main work. This should itself deal with its
41  // own exceptions, but if for some reason one is thrown, it will be caught
42  // in SimpleActionServer and terminate the action itself.
43  typedef std::function<void ()> ExecuteCallback;
44 
45  // Callback function to notify the user that an exception was thrown that
46  // the simple action server caught (or another failure) and the action was
47  // terminated. To avoid using, catch exceptions in your application such that
48  // the SimpleActionServer will never need to terminate based on failed action
49  // ExecuteCallback.
50  typedef std::function<void ()> CompletionCallback;
51 
61  template<typename NodeT>
63  NodeT node,
64  const std::string & action_name,
65  ExecuteCallback execute_callback,
66  CompletionCallback completion_callback = nullptr,
67  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
68  bool spin_thread = false,
69  const rcl_action_server_options_t & options = rcl_action_server_get_default_options())
71  node->get_node_base_interface(),
72  node->get_node_clock_interface(),
73  node->get_node_logging_interface(),
74  node->get_node_waitables_interface(),
75  action_name, execute_callback, completion_callback, server_timeout, spin_thread, options)
76  {}
77 
88  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
89  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
90  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
91  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
92  const std::string & action_name,
93  ExecuteCallback execute_callback,
94  CompletionCallback completion_callback = nullptr,
95  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
96  bool spin_thread = false,
97  const rcl_action_server_options_t & options = rcl_action_server_get_default_options())
98  : node_base_interface_(node_base_interface),
99  node_clock_interface_(node_clock_interface),
100  node_logging_interface_(node_logging_interface),
101  node_waitables_interface_(node_waitables_interface),
102  action_name_(action_name),
103  execute_callback_(execute_callback),
104  completion_callback_(completion_callback),
105  server_timeout_(server_timeout),
106  spin_thread_(spin_thread)
107  {
108  using namespace std::placeholders; // NOLINT
109  if (spin_thread_) {
110  callback_group_ = node_base_interface->create_callback_group(
111  rclcpp::CallbackGroupType::MutuallyExclusive, false);
112  }
113  action_server_ = rclcpp_action::create_server<ActionT>(
114  node_base_interface_,
115  node_clock_interface_,
116  node_logging_interface_,
117  node_waitables_interface_,
118  action_name_,
119  std::bind(&SimpleActionServer::handle_goal, this, _1, _2),
120  std::bind(&SimpleActionServer::handle_cancel, this, _1),
121  std::bind(&SimpleActionServer::handle_accepted, this, _1),
122  options,
123  callback_group_);
124  if (spin_thread_) {
125  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
126  executor_->add_callback_group(callback_group_, node_base_interface_);
127  executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
128  }
129  }
130 
137  rclcpp_action::GoalResponse handle_goal(
138  const rclcpp_action::GoalUUID & /*uuid*/,
139  std::shared_ptr<const typename ActionT::Goal>/*goal*/)
140  {
141  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
142 
143  if (!server_active_) {
144  return rclcpp_action::GoalResponse::REJECT;
145  }
146 
147  debug_msg("Received request for goal acceptance");
148  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
149  }
150 
157  rclcpp_action::CancelResponse handle_cancel(
158  const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
159  {
160  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
161 
162  if (!handle->is_active()) {
163  warn_msg(
164  "Received request for goal cancellation,"
165  "but the handle is inactive, so reject the request");
166  return rclcpp_action::CancelResponse::REJECT;
167  }
168 
169  debug_msg("Received request for goal cancellation");
170  return rclcpp_action::CancelResponse::ACCEPT;
171  }
172 
177  void handle_accepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
178  {
179  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
180  debug_msg("Receiving a new goal");
181 
182  if (is_active(current_handle_) || is_running()) {
183  debug_msg("An older goal is active, moving the new goal to a pending slot.");
184 
185  if (is_active(pending_handle_)) {
186  debug_msg(
187  "The pending slot is occupied."
188  " The previous pending goal will be terminated and replaced.");
189  terminate(pending_handle_);
190  }
191  pending_handle_ = handle;
192  preempt_requested_ = true;
193  } else {
194  if (is_active(pending_handle_)) {
195  // Shouldn't reach a state with a pending goal but no current one.
196  error_msg("Forgot to handle a preemption. Terminating the pending goal.");
197  terminate(pending_handle_);
198  preempt_requested_ = false;
199  }
200 
201  current_handle_ = handle;
202 
203  // Return quickly to avoid blocking the executor, so spin up a new thread
204  debug_msg("Executing goal asynchronously.");
205  execution_future_ = std::async(std::launch::async, [this]() {work();});
206  }
207  }
208 
212  void work()
213  {
214  while (rclcpp::ok() && !stop_execution_ && is_active(current_handle_)) {
215  debug_msg("Executing the goal...");
216  try {
217  execute_callback_();
218  } catch (std::exception & ex) {
219  RCLCPP_ERROR(
220  node_logging_interface_->get_logger(),
221  "Action server failed while executing action callback: \"%s\"", ex.what());
222  terminate_all();
223  completion_callback_();
224  return;
225  }
226 
227  debug_msg("Blocking processing of new goal handles.");
228  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
229 
230  if (stop_execution_) {
231  warn_msg("Stopping the thread per request.");
232  terminate_all();
233  completion_callback_();
234  break;
235  }
236 
237  if (is_active(current_handle_)) {
238  warn_msg("Current goal was not completed successfully.");
239  terminate(current_handle_);
240  completion_callback_();
241  }
242 
243  if (is_active(pending_handle_)) {
244  debug_msg("Executing a pending handle on the existing thread.");
246  } else {
247  debug_msg("Done processing available goals.");
248  break;
249  }
250  }
251  debug_msg("Worker thread done.");
252  }
253 
257  void activate()
258  {
259  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
260  server_active_ = true;
261  stop_execution_ = false;
262  }
263 
267  void deactivate()
268  {
269  debug_msg("Deactivating...");
270 
271  {
272  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
273  server_active_ = false;
274  stop_execution_ = true;
275  }
276 
277  if (!execution_future_.valid()) {
278  return;
279  }
280 
281  if (is_running()) {
282  warn_msg(
283  "Requested to deactivate server but goal is still executing."
284  " Should check if action server is running before deactivating.");
285  }
286 
287  using namespace std::chrono; //NOLINT
288  auto start_time = steady_clock::now();
289  while (execution_future_.wait_for(milliseconds(100)) != std::future_status::ready) {
290  info_msg("Waiting for async process to finish.");
291  if (steady_clock::now() - start_time >= server_timeout_) {
292  terminate_all();
293  if (completion_callback_) {completion_callback_();}
294  error_msg("Action callback is still running and missed deadline to stop");
295  }
296  }
297 
298  debug_msg("Deactivation completed.");
299  }
300 
305  bool is_running()
306  {
307  return execution_future_.valid() &&
308  (execution_future_.wait_for(std::chrono::milliseconds(0)) ==
309  std::future_status::timeout);
310  }
311 
317  {
318  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
319  return server_active_;
320  }
321 
326  bool is_preempt_requested() const
327  {
328  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
329  return preempt_requested_;
330  }
331 
336  const std::shared_ptr<const typename ActionT::Goal> accept_pending_goal()
337  {
338  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
339 
340  if (!pending_handle_ || !pending_handle_->is_active()) {
341  error_msg("Attempting to get pending goal when not available");
342  return std::shared_ptr<const typename ActionT::Goal>();
343  }
344 
345  if (is_active(current_handle_) && current_handle_ != pending_handle_) {
346  debug_msg("Cancelling the previous goal");
347  current_handle_->abort(empty_result());
348  }
349 
350  current_handle_ = pending_handle_;
351  pending_handle_.reset();
352  preempt_requested_ = false;
353 
354  debug_msg("Preempted goal");
355 
356  return current_handle_->get_goal();
357  }
358 
363  {
364  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
365 
366  if (!pending_handle_ || !pending_handle_->is_active()) {
367  error_msg("Attempting to terminate pending goal when not available");
368  return;
369  }
370 
371  terminate(pending_handle_);
372  preempt_requested_ = false;
373 
374  debug_msg("Pending goal terminated");
375  }
376 
381  const std::shared_ptr<const typename ActionT::Goal> get_current_goal() const
382  {
383  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
384 
385  if (!is_active(current_handle_)) {
386  error_msg("A goal is not available or has reached a final state");
387  return std::shared_ptr<const typename ActionT::Goal>();
388  }
389 
390  return current_handle_->get_goal();
391  }
392 
393  const rclcpp_action::GoalUUID get_current_goal_id() const
394  {
395  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
396 
397  if (!is_active(current_handle_)) {
398  error_msg("A goal is not available or has reached a final state");
399  return rclcpp_action::GoalUUID();
400  }
401 
402  return current_handle_->get_goal_id();
403  }
404 
409  const std::shared_ptr<const typename ActionT::Goal> get_pending_goal() const
410  {
411  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
412 
413  if (!pending_handle_ || !pending_handle_->is_active()) {
414  error_msg("Attempting to get pending goal when not available");
415  return std::shared_ptr<const typename ActionT::Goal>();
416  }
417 
418  return pending_handle_->get_goal();
419  }
420 
425  bool is_cancel_requested() const
426  {
427  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
428 
429  // A cancel request is assumed if either handle is canceled by the client.
430 
431  if (current_handle_ == nullptr) {
432  error_msg("Checking for cancel but current goal is not available");
433  return false;
434  }
435 
436  if (pending_handle_ != nullptr) {
437  return pending_handle_->is_canceling();
438  }
439 
440  return current_handle_->is_canceling();
441  }
442 
448  typename std::shared_ptr<typename ActionT::Result> result =
449  std::make_shared<typename ActionT::Result>())
450  {
451  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
452  terminate(current_handle_, result);
453  terminate(pending_handle_, result);
454  preempt_requested_ = false;
455  }
456 
462  typename std::shared_ptr<typename ActionT::Result> result =
463  std::make_shared<typename ActionT::Result>())
464  {
465  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
466  terminate(current_handle_, result);
467  }
468 
474  typename std::shared_ptr<typename ActionT::Result> result =
475  std::make_shared<typename ActionT::Result>())
476  {
477  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
478 
479  if (is_active(current_handle_)) {
480  debug_msg("Setting succeed on current goal.");
481  current_handle_->succeed(result);
482  current_handle_.reset();
483  }
484  }
485 
490  void publish_feedback(typename std::shared_ptr<typename ActionT::Feedback> feedback)
491  {
492  if (!is_active(current_handle_)) {
493  error_msg("Trying to publish feedback when the current goal handle is not active");
494  return;
495  }
496 
497  current_handle_->publish_feedback(feedback);
498  }
499 
500 protected:
501  // The SimpleActionServer isn't itself a node, so it needs interfaces to one
502  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
503  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface_;
504  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_;
505  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface_;
506  std::string action_name_;
507 
508  ExecuteCallback execute_callback_;
509  CompletionCallback completion_callback_;
510  std::future<void> execution_future_;
511  bool stop_execution_{false};
512 
513  mutable std::recursive_mutex update_mutex_;
514  bool server_active_{false};
515  bool preempt_requested_{false};
516  std::chrono::milliseconds server_timeout_;
517 
518  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> current_handle_;
519  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;
520 
521  typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
522  bool spin_thread_;
523  rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr};
524  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
525  std::unique_ptr<nav2_util::NodeThread> executor_thread_;
526 
530  constexpr auto empty_result() const
531  {
532  return std::make_shared<typename ActionT::Result>();
533  }
534 
540  constexpr bool is_active(
541  const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle) const
542  {
543  return handle != nullptr && handle->is_active();
544  }
545 
551  void terminate(
552  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> & handle,
553  typename std::shared_ptr<typename ActionT::Result> result =
554  std::make_shared<typename ActionT::Result>())
555  {
556  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
557 
558  if (is_active(handle)) {
559  if (handle->is_canceling()) {
560  info_msg("Client requested to cancel the goal. Cancelling.");
561  handle->canceled(result);
562  } else {
563  warn_msg("Aborting handle.");
564  handle->abort(result);
565  }
566  handle.reset();
567  }
568  }
569 
573  void info_msg(const std::string & msg) const
574  {
575  RCLCPP_INFO(
576  node_logging_interface_->get_logger(),
577  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
578  }
579 
583  void debug_msg(const std::string & msg) const
584  {
585  RCLCPP_DEBUG(
586  node_logging_interface_->get_logger(),
587  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
588  }
589 
593  void error_msg(const std::string & msg) const
594  {
595  RCLCPP_ERROR(
596  node_logging_interface_->get_logger(),
597  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
598  }
599 
603  void warn_msg(const std::string & msg) const
604  {
605  RCLCPP_WARN(
606  node_logging_interface_->get_logger(),
607  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
608  }
609 };
610 
611 } // namespace nav2_util
612 
613 #endif // NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
An action server wrapper to make applications simpler using Actions.
void publish_feedback(typename std::shared_ptr< typename ActionT::Feedback > feedback)
Publish feedback to the action server clients.
void succeeded_current(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Return success of the active action.
constexpr bool is_active(const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle) const
Whether a given goal handle is currently active.
void terminate_current(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate the active action.
rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle)
Accepts cancellation requests of action server.
const std::shared_ptr< const typename ActionT::Goal > get_pending_goal() const
Get the pending goal object.
void terminate_pending_goal()
Terminate pending goals.
void terminate(std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> &handle, typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate a particular action with a result.
void debug_msg(const std::string &msg) const
Debug logging.
SimpleActionServer(NodeT node, const std::string &action_name, ExecuteCallback execute_callback, CompletionCallback completion_callback=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const rcl_action_server_options_t &options=rcl_action_server_get_default_options())
An constructor for SimpleActionServer.
SimpleActionServer(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface, rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface, const std::string &action_name, ExecuteCallback execute_callback, CompletionCallback completion_callback=nullptr, std::chrono::milliseconds server_timeout=std::chrono::milliseconds(500), bool spin_thread=false, const rcl_action_server_options_t &options=rcl_action_server_get_default_options())
An constructor for SimpleActionServer.
bool is_cancel_requested() const
Whether or not a cancel command has come in.
constexpr auto empty_result() const
Generate an empty result object for an action type.
void error_msg(const std::string &msg) const
Error logging.
bool is_running()
Whether the action server is munching on a goal.
void info_msg(const std::string &msg) const
Info logging.
void activate()
Active action server.
void work()
Computed background work and processes stop requests.
void terminate_all(typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
Terminate all pending and active actions.
bool is_preempt_requested() const
Whether the action server has been asked to be preempted with a new goal.
rclcpp_action::GoalResponse handle_goal(const rclcpp_action::GoalUUID &, std::shared_ptr< const typename ActionT::Goal >)
handle the goal requested: accept or reject. This implementation always accepts.
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
void deactivate()
Deactive action server.
bool is_server_active()
Whether the action server is active or not.
void handle_accepted(const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle)
Handles accepted goals and adds to preempted queue to switch to.
const std::shared_ptr< const typename ActionT::Goal > get_current_goal() const
Get the current goal object.
void warn_msg(const std::string &msg) const
Warn logging.