Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
nav2_util::SimpleActionServer< ActionT > Class Template Reference

An action server wrapper to make applications simpler using Actions. More...

#include <nav2_util/include/nav2_util/simple_action_server.hpp>

Collaboration diagram for nav2_util::SimpleActionServer< ActionT >:
Collaboration graph
[legend]

Public Types

typedef std::function< void()> ExecuteCallback
 
typedef std::function< void()> CompletionCallback
 

Public Member Functions

template<typename NodeT >
 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. More...
 
 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. More...
 
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. More...
 
rclcpp_action::CancelResponse handle_cancel (const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle)
 Accepts cancellation requests of action server. More...
 
void handle_accepted (const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle)
 Handles accepted goals and adds to preempted queue to switch to. More...
 
void work ()
 Computed background work and processes stop requests.
 
void activate ()
 Active action server.
 
void deactivate ()
 Deactive action server.
 
bool is_running ()
 Whether the action server is munching on a goal. More...
 
bool is_server_active ()
 Whether the action server is active or not. More...
 
bool is_preempt_requested () const
 Whether the action server has been asked to be preempted with a new goal. More...
 
const std::shared_ptr< const typename ActionT::Goal > accept_pending_goal ()
 Accept pending goals. More...
 
void terminate_pending_goal ()
 Terminate pending goals.
 
const std::shared_ptr< const typename ActionT::Goal > get_current_goal () const
 Get the current goal object. More...
 
const rclcpp_action::GoalUUID get_current_goal_id () const
 
const std::shared_ptr< const typename ActionT::Goal > get_pending_goal () const
 Get the pending goal object. More...
 
bool is_cancel_requested () const
 Whether or not a cancel command has come in. More...
 
void terminate_all (typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
 Terminate all pending and active actions. More...
 
void terminate_current (typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
 Terminate the active action. More...
 
void succeeded_current (typename std::shared_ptr< typename ActionT::Result > result=std::make_shared< typename ActionT::Result >())
 Return success of the active action. More...
 
void publish_feedback (typename std::shared_ptr< typename ActionT::Feedback > feedback)
 Publish feedback to the action server clients. More...
 

Protected Member Functions

constexpr auto empty_result () const
 Generate an empty result object for an action type.
 
constexpr bool is_active (const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> handle) const
 Whether a given goal handle is currently active. More...
 
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. More...
 
void info_msg (const std::string &msg) const
 Info logging.
 
void debug_msg (const std::string &msg) const
 Debug logging.
 
void error_msg (const std::string &msg) const
 Error logging.
 
void warn_msg (const std::string &msg) const
 Warn logging.
 

Protected Attributes

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_
 
std::string action_name_
 
ExecuteCallback execute_callback_
 
CompletionCallback completion_callback_
 
std::future< void > execution_future_
 
bool stop_execution_ {false}
 
std::recursive_mutex update_mutex_
 
bool server_active_ {false}
 
bool preempt_requested_ {false}
 
std::chrono::milliseconds server_timeout_
 
std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT > > current_handle_
 
std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT > > pending_handle_
 
rclcpp_action::Server< ActionT >::SharedPtr action_server_
 
bool spin_thread_
 
rclcpp::CallbackGroup::SharedPtr callback_group_ {nullptr}
 
rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_
 
std::unique_ptr< nav2_util::NodeThreadexecutor_thread_
 

Detailed Description

template<typename ActionT>
class nav2_util::SimpleActionServer< ActionT >

An action server wrapper to make applications simpler using Actions.

Definition at line 37 of file simple_action_server.hpp.

Constructor & Destructor Documentation

◆ SimpleActionServer() [1/2]

template<typename ActionT >
template<typename NodeT >
nav2_util::SimpleActionServer< ActionT >::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() 
)
inlineexplicit

An constructor for SimpleActionServer.

Parameters
nodePtr to node to make actions
action_nameName of the action to call
execute_callbackExecution callback function of Action
server_timeoutTimeout to to react to stop or preemption requests
spin_threadWhether to spin with a dedicated thread internally
optionsOptions to pass to the underlying rcl_action_server_t

Definition at line 62 of file simple_action_server.hpp.

◆ SimpleActionServer() [2/2]

template<typename ActionT >
nav2_util::SimpleActionServer< ActionT >::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() 
)
inlineexplicit

An constructor for SimpleActionServer.

Parameters
<nodeinterfaces> Abstract node interfaces to make actions
action_nameName of the action to call
execute_callbackExecution callback function of Action
server_timeoutTimeout to to react to stop or preemption requests
spin_threadWhether to spin with a dedicated thread internally
optionsOptions to pass to the underlying rcl_action_server_t

Definition at line 87 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::handle_accepted(), nav2_util::SimpleActionServer< ActionT >::handle_cancel(), and nav2_util::SimpleActionServer< ActionT >::handle_goal().

Here is the call graph for this function:

Member Function Documentation

◆ accept_pending_goal()

template<typename ActionT >
const std::shared_ptr<const typename ActionT::Goal> nav2_util::SimpleActionServer< ActionT >::accept_pending_goal ( )
inline

Accept pending goals.

Returns
Goal Ptr to the goal that's going to be accepted

Definition at line 336 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::debug_msg(), nav2_util::SimpleActionServer< ActionT >::empty_result(), nav2_util::SimpleActionServer< ActionT >::error_msg(), and nav2_util::SimpleActionServer< ActionT >::is_active().

Referenced by nav2_util::SimpleActionServer< ActionT >::work().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ get_current_goal()

template<typename ActionT >
const std::shared_ptr<const typename ActionT::Goal> nav2_util::SimpleActionServer< ActionT >::get_current_goal ( ) const
inline

Get the current goal object.

Returns
Goal Ptr to the goal that's being processed currently

Definition at line 381 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::error_msg(), and nav2_util::SimpleActionServer< ActionT >::is_active().

Here is the call graph for this function:

◆ get_pending_goal()

template<typename ActionT >
const std::shared_ptr<const typename ActionT::Goal> nav2_util::SimpleActionServer< ActionT >::get_pending_goal ( ) const
inline

Get the pending goal object.

Returns
Goal Ptr to the goal that's pending

Definition at line 409 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::error_msg().

Here is the call graph for this function:

◆ handle_accepted()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::handle_accepted ( const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >>  handle)
inline

Handles accepted goals and adds to preempted queue to switch to.

Parameters
GoalA server goal handle to cancel

Definition at line 177 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::debug_msg(), nav2_util::SimpleActionServer< ActionT >::error_msg(), nav2_util::SimpleActionServer< ActionT >::is_active(), nav2_util::SimpleActionServer< ActionT >::is_running(), nav2_util::SimpleActionServer< ActionT >::terminate(), and nav2_util::SimpleActionServer< ActionT >::work().

Referenced by nav2_util::SimpleActionServer< ActionT >::SimpleActionServer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_cancel()

template<typename ActionT >
rclcpp_action::CancelResponse nav2_util::SimpleActionServer< ActionT >::handle_cancel ( const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >>  handle)
inline

Accepts cancellation requests of action server.

Parameters
uuidGoal ID
GoalA server goal handle to cancel
Returns
CancelResponse response of the goal cancelled

Definition at line 157 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::debug_msg(), and nav2_util::SimpleActionServer< ActionT >::warn_msg().

Referenced by nav2_util::SimpleActionServer< ActionT >::SimpleActionServer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ handle_goal()

template<typename ActionT >
rclcpp_action::GoalResponse nav2_util::SimpleActionServer< ActionT >::handle_goal ( const rclcpp_action::GoalUUID &  ,
std::shared_ptr< const typename ActionT::Goal >   
)
inline

handle the goal requested: accept or reject. This implementation always accepts.

Parameters
uuidGoal ID
GoalA shared pointer to the specific goal
Returns
GoalResponse response of the goal processed

Definition at line 137 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::debug_msg().

Referenced by nav2_util::SimpleActionServer< ActionT >::SimpleActionServer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ is_active()

template<typename ActionT >
constexpr bool nav2_util::SimpleActionServer< ActionT >::is_active ( const std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >>  handle) const
inlineconstexprprotected

◆ is_cancel_requested()

template<typename ActionT >
bool nav2_util::SimpleActionServer< ActionT >::is_cancel_requested ( ) const
inline

Whether or not a cancel command has come in.

Returns
bool Whether a cancel command has been requested or not

Definition at line 425 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::error_msg().

Here is the call graph for this function:

◆ is_preempt_requested()

template<typename ActionT >
bool nav2_util::SimpleActionServer< ActionT >::is_preempt_requested ( ) const
inline

Whether the action server has been asked to be preempted with a new goal.

Returns
bool If there's a preemption request or not

Definition at line 326 of file simple_action_server.hpp.

◆ is_running()

template<typename ActionT >
bool nav2_util::SimpleActionServer< ActionT >::is_running ( )
inline

Whether the action server is munching on a goal.

Returns
bool If its running or not

Definition at line 305 of file simple_action_server.hpp.

Referenced by nav2_util::SimpleActionServer< ActionT >::deactivate(), and nav2_util::SimpleActionServer< ActionT >::handle_accepted().

Here is the caller graph for this function:

◆ is_server_active()

template<typename ActionT >
bool nav2_util::SimpleActionServer< ActionT >::is_server_active ( )
inline

Whether the action server is active or not.

Returns
bool If its active or not

Definition at line 316 of file simple_action_server.hpp.

◆ publish_feedback()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::publish_feedback ( typename std::shared_ptr< typename ActionT::Feedback >  feedback)
inline

Publish feedback to the action server clients.

Parameters
feedbackA feedback object to send to the clients

Definition at line 490 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::error_msg(), and nav2_util::SimpleActionServer< ActionT >::is_active().

Here is the call graph for this function:

◆ succeeded_current()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::succeeded_current ( typename std::shared_ptr< typename ActionT::Result >  result = std::make_shared<typename ActionT::Result>())
inline

Return success of the active action.

Parameters
resultA result object to send to the terminated actions

Definition at line 473 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::debug_msg(), and nav2_util::SimpleActionServer< ActionT >::is_active().

Here is the call graph for this function:

◆ terminate()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::terminate ( std::shared_ptr< rclcpp_action::ServerGoalHandle< ActionT >> &  handle,
typename std::shared_ptr< typename ActionT::Result >  result = std::make_shared<typename ActionT::Result>() 
)
inlineprotected

◆ terminate_all()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::terminate_all ( typename std::shared_ptr< typename ActionT::Result >  result = std::make_shared<typename ActionT::Result>())
inline

Terminate all pending and active actions.

Parameters
resultA result object to send to the terminated actions

Definition at line 447 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::terminate().

Referenced by nav2_util::SimpleActionServer< ActionT >::deactivate(), and nav2_util::SimpleActionServer< ActionT >::work().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ terminate_current()

template<typename ActionT >
void nav2_util::SimpleActionServer< ActionT >::terminate_current ( typename std::shared_ptr< typename ActionT::Result >  result = std::make_shared<typename ActionT::Result>())
inline

Terminate the active action.

Parameters
resultA result object to send to the terminated action

Definition at line 461 of file simple_action_server.hpp.

References nav2_util::SimpleActionServer< ActionT >::terminate().

Here is the call graph for this function:

The documentation for this class was generated from the following file: