Template Class SimpleActionServer

Class Documentation

template<typename ActionT>
class SimpleActionServer

An action server wrapper to make applications simpler using Actions.

Public Types

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

Public Functions

template<typename NodeT>
inline explicit 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.

Parameters:
  • node – Ptr to node to make actions

  • action_name – Name of the action to call

  • execute_callback – Execution callback function of Action

  • server_timeout – Timeout to to react to stop or preemption requests

  • spin_thread – Whether to spin with a dedicated thread internally

  • options – Options to pass to the underlying rcl_action_server_t

inline explicit 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.

Parameters:
  • <node – interfaces> Abstract node interfaces to make actions

  • action_name – Name of the action to call

  • execute_callback – Execution callback function of Action

  • server_timeout – Timeout to to react to stop or preemption requests

  • spin_thread – Whether to spin with a dedicated thread internally

  • options – Options to pass to the underlying rcl_action_server_t

inline 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.

Parameters:
  • uuid – Goal ID

  • Goal – A shared pointer to the specific goal

Returns:

GoalResponse response of the goal processed

inline rclcpp_action::CancelResponse handle_cancel(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)

Accepts cancellation requests of action server.

Parameters:
  • uuid – Goal ID

  • Goal – A server goal handle to cancel

Returns:

CancelResponse response of the goal cancelled

inline void handle_accepted(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle)

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

Parameters:

Goal – A server goal handle to cancel

inline void work()

Computed background work and processes stop requests.

inline void activate()

Active action server.

inline void deactivate()

Deactive action server.

inline bool is_running()

Whether the action server is munching on a goal.

Returns:

bool If its running or not

inline bool is_server_active()

Whether the action server is active or not.

Returns:

bool If its active or not

inline bool is_preempt_requested() const

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

Returns:

bool If there’s a preemption request or not

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

Accept pending goals.

Returns:

Goal Ptr to the goal that’s going to be accepted

inline void terminate_pending_goal()

Terminate pending goals.

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

Get the current goal object.

Returns:

Goal Ptr to the goal that’s being processed currently

inline const rclcpp_action::GoalUUID get_current_goal_id() const
inline const std::shared_ptr<const typename ActionT::Goal> get_pending_goal() const

Get the pending goal object.

Returns:

Goal Ptr to the goal that’s pending

inline bool is_cancel_requested() const

Whether or not a cancel command has come in.

Returns:

bool Whether a cancel command has been requested or not

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

Terminate all pending and active actions.

Parameters:

result – A result object to send to the terminated actions

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

Terminate the active action.

Parameters:

result – A result object to send to the terminated action

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

Return success of the active action.

Parameters:

result – A result object to send to the terminated actions

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

Publish feedback to the action server clients.

Parameters:

feedback – A feedback object to send to the clients

Protected Functions

inline constexpr auto empty_result() const

Generate an empty result object for an action type.

inline constexpr bool is_active(const std::shared_ptr<rclcpp_action::ServerGoalHandle<ActionT>> handle) const

Whether a given goal handle is currently active.

Parameters:

handle – Goal handle to check

Returns:

Whether this goal handle is active

inline 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.

Parameters:
  • handle – goal handle to terminate

  • the – Results object to terminate the action with

inline void info_msg(const std::string &msg) const

Info logging.

inline void debug_msg(const std::string &msg) const

Debug logging.

inline void error_msg(const std::string &msg) const

Error logging.

inline 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}
mutable 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::NodeThread> executor_thread_