15 #ifndef NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
16 #define NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
24 #include <type_traits>
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"
38 template<
typename ActionT>
45 typedef std::function<void ()> ExecuteCallback;
52 typedef std::function<void ()> CompletionCallback;
65 template<
typename NodeT>
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)
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)
117 using namespace std::placeholders;
118 use_realtime_prioritization_ = realtime;
120 callback_group_ = node_base_interface->create_callback_group(
121 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
123 action_server_ = rclcpp_action::create_server<ActionT>(
124 node_base_interface_,
125 node_clock_interface_,
126 node_logging_interface_,
127 node_waitables_interface_,
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_);
149 const rclcpp_action::GoalUUID & ,
150 std::shared_ptr<const typename ActionT::Goal>)
152 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
154 if (!server_active_) {
156 node_logging_interface_->get_logger(),
157 "Action server is inactive. Rejecting the goal.");
158 return rclcpp_action::GoalResponse::REJECT;
161 debug_msg(
"Received request for goal acceptance");
162 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
172 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
174 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
176 if (!handle->is_active()) {
178 "Received request for goal cancellation,"
179 "but the handle is inactive, so reject the request");
180 return rclcpp_action::CancelResponse::REJECT;
183 debug_msg(
"Received request for goal cancellation");
184 return rclcpp_action::CancelResponse::ACCEPT;
192 if (use_realtime_prioritization_) {
193 nav2_util::setSoftRealTimePriority();
194 debug_msg(
"Soft realtime prioritization successfully set!");
202 void handle_accepted(
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
204 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
208 debug_msg(
"An older goal is active, moving the new goal to a pending slot.");
212 "The pending slot is occupied."
213 " The previous pending goal will be terminated and replaced.");
216 pending_handle_ = handle;
217 preempt_requested_ =
true;
221 error_msg(
"Forgot to handle a preemption. Terminating the pending goal.");
223 preempt_requested_ =
false;
226 current_handle_ = handle;
229 debug_msg(
"Executing goal asynchronously.");
230 execution_future_ = std::async(
231 std::launch::async, [
this]() {
243 while (rclcpp::ok() && !stop_execution_ &&
is_active(current_handle_)) {
247 }
catch (std::exception & ex) {
249 node_logging_interface_->get_logger(),
250 "Action server failed while executing action callback: \"%s\"", ex.what());
252 if (completion_callback_) {completion_callback_();}
256 debug_msg(
"Blocking processing of new goal handles.");
257 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
259 if (stop_execution_) {
260 warn_msg(
"Stopping the thread per request.");
262 if (completion_callback_) {completion_callback_();}
267 warn_msg(
"Current goal was not completed successfully.");
269 if (completion_callback_) {completion_callback_();}
273 debug_msg(
"Executing a pending handle on the existing thread.");
276 debug_msg(
"Done processing available goals.");
288 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
289 server_active_ =
true;
290 stop_execution_ =
false;
301 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
302 server_active_ =
false;
303 stop_execution_ =
true;
306 if (!execution_future_.valid()) {
312 "Requested to deactivate server but goal is still executing."
313 " Should check if action server is running before deactivating.");
316 using namespace std::chrono;
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_) {
322 if (completion_callback_) {completion_callback_();}
323 error_msg(
"Action callback is still running and missed deadline to stop");
336 return execution_future_.valid() &&
337 (execution_future_.wait_for(std::chrono::milliseconds(0)) ==
338 std::future_status::timeout);
347 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
348 return server_active_;
357 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
358 return preempt_requested_;
367 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
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>();
374 if (
is_active(current_handle_) && current_handle_ != pending_handle_) {
375 debug_msg(
"Cancelling the previous goal");
379 current_handle_ = pending_handle_;
380 pending_handle_.reset();
381 preempt_requested_ =
false;
385 return current_handle_->get_goal();
393 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
395 if (!pending_handle_ || !pending_handle_->is_active()) {
396 error_msg(
"Attempting to terminate pending goal when not available");
401 preempt_requested_ =
false;
412 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
415 error_msg(
"A goal is not available or has reached a final state");
416 return std::shared_ptr<const typename ActionT::Goal>();
419 return current_handle_->get_goal();
422 const rclcpp_action::GoalUUID get_current_goal_id()
const
424 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
427 error_msg(
"A goal is not available or has reached a final state");
428 return rclcpp_action::GoalUUID();
431 return current_handle_->get_goal_id();
440 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
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>();
447 return pending_handle_->get_goal();
456 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
460 if (current_handle_ ==
nullptr) {
461 error_msg(
"Checking for cancel but current goal is not available");
465 if (pending_handle_ !=
nullptr) {
466 return pending_handle_->is_canceling();
469 return current_handle_->is_canceling();
477 typename std::shared_ptr<typename ActionT::Result> result =
478 std::make_shared<typename ActionT::Result>())
480 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
483 preempt_requested_ =
false;
491 typename std::shared_ptr<typename ActionT::Result> result =
492 std::make_shared<typename ActionT::Result>())
494 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
503 typename std::shared_ptr<typename ActionT::Result> result =
504 std::make_shared<typename ActionT::Result>())
506 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
509 debug_msg(
"Setting succeed on current goal.");
510 current_handle_->succeed(result);
511 current_handle_.reset();
522 error_msg(
"Trying to publish feedback when the current goal handle is not active");
526 current_handle_->publish_feedback(feedback);
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_;
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};
543 mutable std::recursive_mutex update_mutex_;
544 bool server_active_{
false};
545 bool preempt_requested_{
false};
546 std::chrono::milliseconds server_timeout_;
548 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> current_handle_;
549 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;
551 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
553 rclcpp::CallbackGroup::SharedPtr callback_group_{
nullptr};
554 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
555 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
562 return std::make_shared<typename ActionT::Result>();
571 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
const
573 return handle !=
nullptr && handle->is_active();
582 template<
typename T,
typename =
void>
585 struct has_error_msg<T, std::void_t<decltype(T::error_msg)>>: std::true_type {};
586 template<
typename T,
typename =
void>
589 struct has_error_code<T, std::void_t<decltype(T::error_code)>>: std::true_type {};
592 void log_error_details_if_available(
const T & result)
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) +
".");
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>())
616 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
619 if (handle->is_canceling()) {
620 info_msg(
"Client requested to cancel the goal. Cancelling.");
621 handle->canceled(result);
623 log_error_details_if_available(result);
624 handle->abort(result);
636 node_logging_interface_->get_logger(),
637 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
646 node_logging_interface_->get_logger(),
647 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
656 node_logging_interface_->get_logger(),
657 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
666 node_logging_interface_->get_logger(),
667 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
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...