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"
36 template<
typename ActionT>
43 typedef std::function<void ()> ExecuteCallback;
50 typedef std::function<void ()> CompletionCallback;
61 template<
typename NodeT>
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)
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)
108 using namespace std::placeholders;
110 callback_group_ = node_base_interface->create_callback_group(
111 rclcpp::CallbackGroupType::MutuallyExclusive,
false);
113 action_server_ = rclcpp_action::create_server<ActionT>(
114 node_base_interface_,
115 node_clock_interface_,
116 node_logging_interface_,
117 node_waitables_interface_,
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_);
138 const rclcpp_action::GoalUUID & ,
139 std::shared_ptr<const typename ActionT::Goal>)
141 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
143 if (!server_active_) {
144 return rclcpp_action::GoalResponse::REJECT;
147 debug_msg(
"Received request for goal acceptance");
148 return rclcpp_action::GoalResponse::ACCEPT_AND_EXECUTE;
158 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
160 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
162 if (!handle->is_active()) {
164 "Received request for goal cancellation,"
165 "but the handle is inactive, so reject the request");
166 return rclcpp_action::CancelResponse::REJECT;
169 debug_msg(
"Received request for goal cancellation");
170 return rclcpp_action::CancelResponse::ACCEPT;
177 void handle_accepted(
const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
179 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
183 debug_msg(
"An older goal is active, moving the new goal to a pending slot.");
187 "The pending slot is occupied."
188 " The previous pending goal will be terminated and replaced.");
191 pending_handle_ = handle;
192 preempt_requested_ =
true;
196 error_msg(
"Forgot to handle a preemption. Terminating the pending goal.");
198 preempt_requested_ =
false;
201 current_handle_ = handle;
204 debug_msg(
"Executing goal asynchronously.");
205 execution_future_ = std::async(std::launch::async, [
this]() {
work();});
214 while (rclcpp::ok() && !stop_execution_ &&
is_active(current_handle_)) {
218 }
catch (std::exception & ex) {
220 node_logging_interface_->get_logger(),
221 "Action server failed while executing action callback: \"%s\"", ex.what());
223 completion_callback_();
227 debug_msg(
"Blocking processing of new goal handles.");
228 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
230 if (stop_execution_) {
231 warn_msg(
"Stopping the thread per request.");
233 completion_callback_();
238 warn_msg(
"Current goal was not completed successfully.");
240 completion_callback_();
244 debug_msg(
"Executing a pending handle on the existing thread.");
247 debug_msg(
"Done processing available goals.");
259 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
260 server_active_ =
true;
261 stop_execution_ =
false;
272 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
273 server_active_ =
false;
274 stop_execution_ =
true;
277 if (!execution_future_.valid()) {
283 "Requested to deactivate server but goal is still executing."
284 " Should check if action server is running before deactivating.");
287 using namespace std::chrono;
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_) {
293 if (completion_callback_) {completion_callback_();}
294 error_msg(
"Action callback is still running and missed deadline to stop");
307 return execution_future_.valid() &&
308 (execution_future_.wait_for(std::chrono::milliseconds(0)) ==
309 std::future_status::timeout);
318 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
319 return server_active_;
328 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
329 return preempt_requested_;
338 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
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>();
345 if (
is_active(current_handle_) && current_handle_ != pending_handle_) {
346 debug_msg(
"Cancelling the previous goal");
350 current_handle_ = pending_handle_;
351 pending_handle_.reset();
352 preempt_requested_ =
false;
356 return current_handle_->get_goal();
364 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
366 if (!pending_handle_ || !pending_handle_->is_active()) {
367 error_msg(
"Attempting to terminate pending goal when not available");
372 preempt_requested_ =
false;
383 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
386 error_msg(
"A goal is not available or has reached a final state");
387 return std::shared_ptr<const typename ActionT::Goal>();
390 return current_handle_->get_goal();
393 const rclcpp_action::GoalUUID get_current_goal_id()
const
395 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
398 error_msg(
"A goal is not available or has reached a final state");
399 return rclcpp_action::GoalUUID();
402 return current_handle_->get_goal_id();
411 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
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>();
418 return pending_handle_->get_goal();
427 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
431 if (current_handle_ ==
nullptr) {
432 error_msg(
"Checking for cancel but current goal is not available");
436 if (pending_handle_ !=
nullptr) {
437 return pending_handle_->is_canceling();
440 return current_handle_->is_canceling();
448 typename std::shared_ptr<typename ActionT::Result> result =
449 std::make_shared<typename ActionT::Result>())
451 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
454 preempt_requested_ =
false;
462 typename std::shared_ptr<typename ActionT::Result> result =
463 std::make_shared<typename ActionT::Result>())
465 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
474 typename std::shared_ptr<typename ActionT::Result> result =
475 std::make_shared<typename ActionT::Result>())
477 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
480 debug_msg(
"Setting succeed on current goal.");
481 current_handle_->succeed(result);
482 current_handle_.reset();
493 error_msg(
"Trying to publish feedback when the current goal handle is not active");
497 current_handle_->publish_feedback(feedback);
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_;
508 ExecuteCallback execute_callback_;
509 CompletionCallback completion_callback_;
510 std::future<void> execution_future_;
511 bool stop_execution_{
false};
513 mutable std::recursive_mutex update_mutex_;
514 bool server_active_{
false};
515 bool preempt_requested_{
false};
516 std::chrono::milliseconds server_timeout_;
518 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> current_handle_;
519 std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> pending_handle_;
521 typename rclcpp_action::Server<ActionT>::SharedPtr action_server_;
523 rclcpp::CallbackGroup::SharedPtr callback_group_{
nullptr};
524 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
525 std::unique_ptr<nav2_util::NodeThread> executor_thread_;
532 return std::make_shared<typename ActionT::Result>();
541 const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)
const
543 return handle !=
nullptr && handle->is_active();
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>())
556 std::lock_guard<std::recursive_mutex> lock(update_mutex_);
559 if (handle->is_canceling()) {
560 info_msg(
"Client requested to cancel the goal. Cancelling.");
561 handle->canceled(result);
564 handle->abort(result);
576 node_logging_interface_->get_logger(),
577 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
586 node_logging_interface_->get_logger(),
587 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
596 node_logging_interface_->get_logger(),
597 "[%s] [ActionServer] %s", action_name_.c_str(), msg.c_str());
606 node_logging_interface_->get_logger(),
607 "[%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 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.