15 #ifndef NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
16 #define NAV2_UTIL__SIMPLE_ACTION_SERVER_HPP_
25 #include "rclcpp/rclcpp.hpp"
26 #include "rclcpp_action/rclcpp_action.hpp"
27 #include "nav2_util/node_thread.hpp"
28 #include "nav2_util/node_utils.hpp"
37 template<
typename ActionT>
44 typedef std::function<void ()> ExecuteCallback;
51 typedef std::function<void ()> CompletionCallback;
64 template<
typename NodeT>
67 const std::string & action_name,
68 ExecuteCallback execute_callback,
69 CompletionCallback completion_callback =
nullptr,
70 std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
71 bool spin_thread =
false,
72 const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
73 const bool realtime =
false)
75 node->get_node_base_interface(),
76 node->get_node_clock_interface(),
77 node->get_node_logging_interface(),
78 node->get_node_waitables_interface(),
79 action_name, execute_callback, completion_callback,
80 server_timeout, spin_thread, options, realtime)
95 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface,
96 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface,
97 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface,
98 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface,
99 const std::string & action_name,
100 ExecuteCallback execute_callback,
101 CompletionCallback completion_callback =
nullptr,
102 std::chrono::milliseconds server_timeout = std::chrono::milliseconds(500),
103 bool spin_thread =
false,
104 const rcl_action_server_options_t & options = rcl_action_server_get_default_options(),
105 const bool realtime =
false)
106 : node_base_interface_(node_base_interface),
107 node_clock_interface_(node_clock_interface),
108 node_logging_interface_(node_logging_interface),
109 node_waitables_interface_(node_waitables_interface),
110 action_name_(action_name),
111 execute_callback_(execute_callback),
112 completion_callback_(completion_callback),
113 server_timeout_(server_timeout),
114 spin_thread_(spin_thread)
116 using namespace std::placeholders;
117 use_realtime_prioritization_ = realtime;
119 callback_group_ = node_base_interface->create_callback_group(
120 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
122 action_server_ = rclcpp_action::create_server<ActionT>(
123 node_base_interface_,
124 node_clock_interface_,
125 node_logging_interface_,
126 node_waitables_interface_,
134 executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
135 executor_->add_callback_group(callback_group_, node_base_interface_);
136 executor_thread_ = std::make_unique<nav2_util::NodeThread>(executor_);
147 const rclcpp_action::GoalUUID & ,
148 std::shared_ptr<const typename ActionT::Goal>)
150 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
152 if (!server_active_) {
154 node_logging_interface_->get_logger(),
155 "Action server is inactive. Rejecting the goal.");
156 return rclcpp_action::GoalResponse::REJECT;
159 debug_msg(
"Received request for goal acceptance");
160 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
170 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
172 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
174 if (!handle->is_active()) {
176 "Received request for goal cancellation,"
177 "but the handle is inactive, so reject the request");
178 return rclcpp_action::CancelResponse::REJECT;
181 debug_msg(
"Received request for goal cancellation");
182 return rclcpp_action::CancelResponse::ACCEPT;
190 if (use_realtime_prioritization_) {
191 nav2_util::setSoftRealTimePriority();
192 debug_msg(
"Soft realtime prioritization successfully set!");
200 void handle_accepted(
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
202 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
206 debug_msg(
"An older goal is active, moving the new goal to a pending slot.");
210 "The pending slot is occupied."
211 " The previous pending goal will be terminated and replaced.");
214 pending_handle_ = handle;
215 preempt_requested_ =
true;
219 error_msg(
"Forgot to handle a preemption. Terminating the pending goal.");
221 preempt_requested_ =
false;
224 current_handle_ = handle;
227 debug_msg(
"Executing goal asynchronously.");
228 execution_future_ = std::async(
229 std::launch::async, [
this]() {
241 while (rclcpp::ok() && !stop_execution_ &&
is_active(current_handle_)) {
245 }
catch (std::exception & ex) {
247 node_logging_interface_->get_logger(),
248 "Action server failed while executing action callback: \"%s\"", ex.what());
250 if (completion_callback_) {completion_callback_();}
254 debug_msg(
"Blocking processing of new goal handles.");
255 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
257 if (stop_execution_) {
258 warn_msg(
"Stopping the thread per request.");
260 if (completion_callback_) {completion_callback_();}
265 warn_msg(
"Current goal was not completed successfully.");
267 if (completion_callback_) {completion_callback_();}
271 debug_msg(
"Executing a pending handle on the existing thread.");
274 debug_msg(
"Done processing available goals.");
286 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
287 server_active_ =
true;
288 stop_execution_ =
false;
299 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
300 server_active_ =
false;
301 stop_execution_ =
true;
304 if (!execution_future_.valid()) {
310 "Requested to deactivate server but goal is still executing."
311 " Should check if action server is running before deactivating.");
314 using namespace std::chrono;
315 auto start_time = steady_clock::now();
316 while (execution_future_.wait_for(milliseconds(100)) != std::future_status::ready) {
317 info_msg(
"Waiting for async process to finish.");
318 if (steady_clock::now() - start_time >= server_timeout_) {
320 if (completion_callback_) {completion_callback_();}
321 error_msg(
"Action callback is still running and missed deadline to stop");
334 return execution_future_.valid() &&
335 (execution_future_.wait_for(std::chrono::milliseconds(0)) ==
336 std::future_status::timeout);
345 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
346 return server_active_;
355 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
356 return preempt_requested_;
365 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
367 if (!pending_handle_ || !pending_handle_->is_active()) {
368 error_msg(
"Attempting to get pending goal when not available");
369 return std::shared_ptr<const typename ActionT::Goal>();
372 if (
is_active(current_handle_) && current_handle_ != pending_handle_) {
373 debug_msg(
"Cancelling the previous goal");
377 current_handle_ = pending_handle_;
378 pending_handle_.reset();
379 preempt_requested_ =
false;
383 return current_handle_->get_goal();
391 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
393 if (!pending_handle_ || !pending_handle_->is_active()) {
394 error_msg(
"Attempting to terminate pending goal when not available");
399 preempt_requested_ =
false;
410 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
413 error_msg(
"A goal is not available or has reached a final state");
414 return std::shared_ptr<const typename ActionT::Goal>();
417 return current_handle_->get_goal();
420 const rclcpp_action::GoalUUID get_current_goal_id()
const
422 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
425 error_msg(
"A goal is not available or has reached a final state");
426 return rclcpp_action::GoalUUID();
429 return current_handle_->get_goal_id();
438 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
440 if (!pending_handle_ || !pending_handle_->is_active()) {
441 error_msg(
"Attempting to get pending goal when not available");
442 return std::shared_ptr<const typename ActionT::Goal>();
445 return pending_handle_->get_goal();
454 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
458 if (current_handle_ ==
nullptr) {
459 error_msg(
"Checking for cancel but current goal is not available");
463 if (pending_handle_ !=
nullptr) {
464 return pending_handle_->is_canceling();
467 return current_handle_->is_canceling();
475 typename std::shared_ptr<typename ActionT::Result> result =
476 std::make_shared<typename ActionT::Result>())
478 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
481 preempt_requested_ =
false;
489 typename std::shared_ptr<typename ActionT::Result> result =
490 std::make_shared<typename ActionT::Result>())
492 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
501 typename std::shared_ptr<typename ActionT::Result> result =
502 std::make_shared<typename ActionT::Result>())
504 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
507 debug_msg(
"Setting succeed on current goal.");
508 current_handle_->succeed(result);
509 current_handle_.reset();
520 error_msg(
"Trying to publish feedback when the current goal handle is not active");
524 current_handle_->publish_feedback(feedback);
529 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_interface_;
530 rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock_interface_;
531 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_interface_;
532 rclcpp::node_interfaces::NodeWaitablesInterface::SharedPtr node_waitables_interface_;
533 std::string action_name_;
535 ExecuteCallback execute_callback_;
536 CompletionCallback completion_callback_;
537 std::future<void> execution_future_;
538 bool stop_execution_{
false};
539 bool use_realtime_prioritization_{
false};
541 mutable std::recursive_mutex update_mutex_;
542 bool server_active_{
false};
543 bool preempt_requested_{
false};
544 std::chrono::milliseconds server_timeout_;
546 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> current_handle_;
547 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;
549 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
551 rclcpp::CallbackGroup::SharedPtr callback_group_{
nullptr};
552 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
553 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
560 return std::make_shared<typename ActionT::Result>();
569 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
const
571 return handle !=
nullptr && handle->is_active();
580 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> & handle,
581 typename std::shared_ptr<typename ActionT::Result> result =
582 std::make_shared<typename ActionT::Result>())
584 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
587 if (handle->is_canceling()) {
588 info_msg(
"Client requested to cancel the goal. Cancelling.");
589 handle->canceled(result);
592 handle->abort(result);
604 node_logging_interface_->get_logger(),
605 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
614 node_logging_interface_->get_logger(),
615 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
624 node_logging_interface_->get_logger(),
625 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
634 node_logging_interface_->get_logger(),
635 "[%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.
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.
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.