Nav2 Navigation Stack - kilted  kilted
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 #include <type_traits>
25 
26 #include "rclcpp/rclcpp.hpp"
27 #include "rclcpp_action/rclcpp_action.hpp"
28 #include "nav2_util/node_thread.hpp"
29 #include "nav2_util/node_utils.hpp"
30 
31 namespace nav2_util
32 {
33 
38 template<typename ActionT>
40 {
41 public:
42  // Callback function to complete main work. This should itself deal with its
43  // own exceptions, but if for some reason one is thrown, it will be caught
44  // in SimpleActionServer and terminate the action itself.
45  typedef std::function<void ()> ExecuteCallback;
46 
47  // Callback function to notify the user that an exception was thrown that
48  // the simple action server caught (or another failure) and the action was
49  // terminated. To avoid using, catch exceptions in your application such that
50  // the SimpleActionServer will never need to terminate based on failed action
51  // ExecuteCallback.
52  typedef std::function<void ()> CompletionCallback;
53 
65  template<typename NodeT>
67  NodeT node,
68  const std::string & action_name,
69  ExecuteCallback execute_callback,
70  CompletionCallback completion_callback = nullptr,
71  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
72  bool spin_thread = false,
73  const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
74  const bool realtime = false)
76  node->get_node_base_interface(),
77  node->get_node_clock_interface(),
78  node->get_node_logging_interface(),
79  node->get_node_waitables_interface(),
80  action_name, execute_callback, completion_callback,
81  server_timeout, spin_thread, options, realtime)
82  {}
83 
96  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
97  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
98  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
99  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
100  const std::string & action_name,
101  ExecuteCallback execute_callback,
102  CompletionCallback completion_callback = nullptr,
103  std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
104  bool spin_thread = false,
105  const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
106  const bool realtime = false)
107  : node_base_interface_(node_base_interface),
108  node_clock_interface_(node_clock_interface),
109  node_logging_interface_(node_logging_interface),
110  node_waitables_interface_(node_waitables_interface),
111  action_name_(action_name),
112  execute_callback_(execute_callback),
113  completion_callback_(completion_callback),
114  server_timeout_(server_timeout),
115  spin_thread_(spin_thread)
116  {
117  using namespace std::placeholders; // NOLINT
118  use_realtime_prioritization_ = realtime;
119  if (spin_thread_) {
120  callback_group_ = node_base_interface->create_callback_group(
121  rclcpp::CallbackGroupType::MutuallyExclusive, false);
122  }
123  action_server_ = rclcpp_action::create_server<ActionT>(
124  node_base_interface_,
125  node_clock_interface_,
126  node_logging_interface_,
127  node_waitables_interface_,
128  action_name_,
129  std::bind(&SimpleActionServer::handle_goal, this, _1, _2),
130  std::bind(&SimpleActionServer::handle_cancel, this, _1),
131  std::bind(&SimpleActionServer::handle_accepted, this, _1),
132  options,
133  callback_group_);
134  if (spin_thread_) {
135  executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
136  executor_->add_callback_group(callback_group_, node_base_interface_);
137  executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
138  }
139  }
140 
148  rclcpp_action::GoalResponse handle_goal(
149  const rclcpp_action::GoalUUID & /*uuid*/,
150  std::shared_ptr<const typename ActionT::Goal>/*goal*/)
151  {
152  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
153 
154  if (!server_active_) {
155  RCLCPP_INFO(
156  node_logging_interface_->get_logger(),
157  "Action server is inactive. Rejecting the goal.");
158  return rclcpp_action::GoalResponse::REJECT;
159  }
160 
161  debug_msg("Received request for goal acceptance");
162  return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
163  }
164 
171  rclcpp_action::CancelResponse handle_cancel(
172  const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
173  {
174  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
175 
176  if (!handle->is_active()) {
177  warn_msg(
178  "Received request for goal cancellation,"
179  "but the handle is inactive, so reject the request");
180  return rclcpp_action::CancelResponse::REJECT;
181  }
182 
183  debug_msg("Received request for goal cancellation");
184  return rclcpp_action::CancelResponse::ACCEPT;
185  }
186 
191  {
192  if (use_realtime_prioritization_) {
193  nav2_util::setSoftRealTimePriority();
194  debug_msg("Soft realtime prioritization successfully set!");
195  }
196  }
197 
202  void handle_accepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
203  {
204  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
205  debug_msg("Receiving a new goal");
206 
207  if (is_active(current_handle_) || is_running()) {
208  debug_msg("An older goal is active, moving the new goal to a pending slot.");
209 
210  if (is_active(pending_handle_)) {
211  debug_msg(
212  "The pending slot is occupied."
213  " The previous pending goal will be terminated and replaced.");
214  terminate(pending_handle_);
215  }
216  pending_handle_ = handle;
217  preempt_requested_ = true;
218  } else {
219  if (is_active(pending_handle_)) {
220  // Shouldn't reach a state with a pending goal but no current one.
221  error_msg("Forgot to handle a preemption. Terminating the pending goal.");
222  terminate(pending_handle_);
223  preempt_requested_ = false;
224  }
225 
226  current_handle_ = handle;
227 
228  // Return quickly to avoid blocking the executor, so spin up a new thread
229  debug_msg("Executing goal asynchronously.");
230  execution_future_ = std::async(
231  std::launch::async, [this]() {
233  work();
234  });
235  }
236  }
237 
241  void work()
242  {
243  while (rclcpp::ok() && !stop_execution_ && is_active(current_handle_)) {
244  debug_msg("Executing the goal...");
245  try {
246  execute_callback_();
247  } catch (std::exception & ex) {
248  RCLCPP_ERROR(
249  node_logging_interface_->get_logger(),
250  "Action server failed while executing action callback: \"%s\"", ex.what());
251  terminate_all();
252  if (completion_callback_) {completion_callback_();}
253  return;
254  }
255 
256  debug_msg("Blocking processing of new goal handles.");
257  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
258 
259  if (stop_execution_) {
260  warn_msg("Stopping the thread per request.");
261  terminate_all();
262  if (completion_callback_) {completion_callback_();}
263  break;
264  }
265 
266  if (is_active(current_handle_)) {
267  warn_msg("Current goal was not completed successfully.");
268  terminate(current_handle_);
269  if (completion_callback_) {completion_callback_();}
270  }
271 
272  if (is_active(pending_handle_)) {
273  debug_msg("Executing a pending handle on the existing thread.");
275  } else {
276  debug_msg("Done processing available goals.");
277  break;
278  }
279  }
280  debug_msg("Worker thread done.");
281  }
282 
286  void activate()
287  {
288  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
289  server_active_ = true;
290  stop_execution_ = false;
291  }
292 
296  void deactivate()
297  {
298  debug_msg("Deactivating...");
299 
300  {
301  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
302  server_active_ = false;
303  stop_execution_ = true;
304  }
305 
306  if (!execution_future_.valid()) {
307  return;
308  }
309 
310  if (is_running()) {
311  warn_msg(
312  "Requested to deactivate server but goal is still executing."
313  " Should check if action server is running before deactivating.");
314  }
315 
316  using namespace std::chrono; //NOLINT
317  auto start_time = steady_clock::now();
318  while (execution_future_.wait_for(milliseconds(100)) != std::future_status::ready) {
319  info_msg("Waiting for async process to finish.");
320  if (steady_clock::now() - start_time >= server_timeout_) {
321  terminate_all();
322  if (completion_callback_) {completion_callback_();}
323  error_msg("Action callback is still running and missed deadline to stop");
324  }
325  }
326 
327  debug_msg("Deactivation completed.");
328  }
329 
334  bool is_running()
335  {
336  return execution_future_.valid() &&
337  (execution_future_.wait_for(std::chrono::milliseconds(0)) ==
338  std::future_status::timeout);
339  }
340 
346  {
347  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
348  return server_active_;
349  }
350 
355  bool is_preempt_requested() const
356  {
357  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
358  return preempt_requested_;
359  }
360 
365  const std::shared_ptr<const typename ActionT::Goal> accept_pending_goal()
366  {
367  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
368 
369  if (!pending_handle_ || !pending_handle_->is_active()) {
370  error_msg("Attempting to get pending goal when not available");
371  return std::shared_ptr<const typename ActionT::Goal>();
372  }
373 
374  if (is_active(current_handle_) && current_handle_ != pending_handle_) {
375  debug_msg("Cancelling the previous goal");
376  current_handle_->abort(empty_result());
377  }
378 
379  current_handle_ = pending_handle_;
380  pending_handle_.reset();
381  preempt_requested_ = false;
382 
383  debug_msg("Preempted goal");
384 
385  return current_handle_->get_goal();
386  }
387 
392  {
393  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
394 
395  if (!pending_handle_ || !pending_handle_->is_active()) {
396  error_msg("Attempting to terminate pending goal when not available");
397  return;
398  }
399 
400  terminate(pending_handle_);
401  preempt_requested_ = false;
402 
403  debug_msg("Pending goal terminated");
404  }
405 
410  const std::shared_ptr<const typename ActionT::Goal> get_current_goal() const
411  {
412  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
413 
414  if (!is_active(current_handle_)) {
415  error_msg("A goal is not available or has reached a final state");
416  return std::shared_ptr<const typename ActionT::Goal>();
417  }
418 
419  return current_handle_->get_goal();
420  }
421 
422  const rclcpp_action::GoalUUID get_current_goal_id() const
423  {
424  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
425 
426  if (!is_active(current_handle_)) {
427  error_msg("A goal is not available or has reached a final state");
428  return rclcpp_action::GoalUUID();
429  }
430 
431  return current_handle_->get_goal_id();
432  }
433 
438  const std::shared_ptr<const typename ActionT::Goal> get_pending_goal() const
439  {
440  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
441 
442  if (!pending_handle_ || !pending_handle_->is_active()) {
443  error_msg("Attempting to get pending goal when not available");
444  return std::shared_ptr<const typename ActionT::Goal>();
445  }
446 
447  return pending_handle_->get_goal();
448  }
449 
454  bool is_cancel_requested() const
455  {
456  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
457 
458  // A cancel request is assumed if either handle is canceled by the client.
459 
460  if (current_handle_ == nullptr) {
461  error_msg("Checking for cancel but current goal is not available");
462  return false;
463  }
464 
465  if (pending_handle_ != nullptr) {
466  return pending_handle_->is_canceling();
467  }
468 
469  return current_handle_->is_canceling();
470  }
471 
477  typename std::shared_ptr<typename ActionT::Result> result =
478  std::make_shared<typename ActionT::Result>())
479  {
480  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
481  terminate(current_handle_, result);
482  terminate(pending_handle_, result);
483  preempt_requested_ = false;
484  }
485 
491  typename std::shared_ptr<typename ActionT::Result> result =
492  std::make_shared<typename ActionT::Result>())
493  {
494  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
495  terminate(current_handle_, result);
496  }
497 
503  typename std::shared_ptr<typename ActionT::Result> result =
504  std::make_shared<typename ActionT::Result>())
505  {
506  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
507 
508  if (is_active(current_handle_)) {
509  debug_msg("Setting succeed on current goal.");
510  current_handle_->succeed(result);
511  current_handle_.reset();
512  }
513  }
514 
519  void publish_feedback(typename std::shared_ptr<typename ActionT::Feedback> feedback)
520  {
521  if (!is_active(current_handle_)) {
522  error_msg("Trying to publish feedback when the current goal handle is not active");
523  return;
524  }
525 
526  current_handle_->publish_feedback(feedback);
527  }
528 
529 protected:
530  // The SimpleActionServer isn't itself a node, so it needs interfaces to one
531  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
532  rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface_;
533  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_;
534  rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface_;
535  std::string action_name_;
536 
537  ExecuteCallback execute_callback_;
538  CompletionCallback completion_callback_;
539  std::future<void> execution_future_;
540  bool stop_execution_{false};
541  bool use_realtime_prioritization_{false};
542 
543  mutable std::recursive_mutex update_mutex_;
544  bool server_active_{false};
545  bool preempt_requested_{false};
546  std::chrono::milliseconds server_timeout_;
547 
548  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> current_handle_;
549  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;
550 
551  typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
552  bool spin_thread_;
553  rclcpp::CallbackGroup::SharedPtr callback_group_{nullptr};
554  rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
555  std::unique_ptr<nav2_util::NodeThread> executor_thread_;
556 
560  constexpr auto empty_result() const
561  {
562  return std::make_shared<typename ActionT::Result>();
563  }
564 
570  constexpr bool is_active(
571  const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle) const
572  {
573  return handle != nullptr && handle->is_active();
574  }
575 
582  template<typename T, typename = void>
583  struct has_error_msg : std::false_type {};
584  template<typename T>
585  struct has_error_msg<T, std::void_t<decltype(T::error_msg)>>: std::true_type {};
586  template<typename T, typename = void>
587  struct has_error_code : std::false_type {};
588  template<typename T>
589  struct has_error_code<T, std::void_t<decltype(T::error_code)>>: std::true_type {};
590 
591  template<typename T>
592  void log_error_details_if_available(const T & result)
593  {
596  {
597  warn_msg("Aborting handle. error_code:" + std::to_string(result->error_code) +
598  ", error_msg:'" + result->error_msg + "'.");
599  } else if constexpr (has_error_code<typename ActionT::Result>::value) {
600  warn_msg("Aborting handle. error_code:" + std::to_string(result->error_code) + ".");
601  } else {
602  warn_msg("Aborting handle.");
603  }
604  }
605 
611  void terminate(
612  std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> & handle,
613  typename std::shared_ptr<typename ActionT::Result> result =
614  std::make_shared<typename ActionT::Result>())
615  {
616  std::lock_guard<std::recursive_mutex> lock(update_mutex_);
617 
618  if (is_active(handle)) {
619  if (handle->is_canceling()) {
620  info_msg("Client requested to cancel the goal. Cancelling.");
621  handle->canceled(result);
622  } else {
623  log_error_details_if_available(result);
624  handle->abort(result);
625  }
626  handle.reset();
627  }
628  }
629 
633  void info_msg(const std::string & msg) const
634  {
635  RCLCPP_INFO(
636  node_logging_interface_->get_logger(),
637  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
638  }
639 
643  void debug_msg(const std::string & msg) const
644  {
645  RCLCPP_DEBUG(
646  node_logging_interface_->get_logger(),
647  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
648  }
649 
653  void error_msg(const std::string & msg) const
654  {
655  RCLCPP_ERROR(
656  node_logging_interface_->get_logger(),
657  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
658  }
659 
663  void warn_msg(const std::string & msg) const
664  {
665  RCLCPP_WARN(
666  node_logging_interface_->get_logger(),
667  "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
668  }
669 };
670 
671 } // namespace nav2_util
672 
673 #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 setSoftRealTimePriority()
Sets thread priority level.
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(), const bool realtime=false)
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 when the server is ac...
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal()
Accept pending goals.
void deactivate()
Deactivate 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.
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(), const bool realtime=false)
An constructor for SimpleActionServer.
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.
SFINAE (Substitution Failure Is Not An Error) to check for existence of error_code and error_msg in A...