Template Class Server

Inheritance Relationships

Base Types

  • public rclcpp_action::ServerBase (Class ServerBase)

  • public std::enable_shared_from_this< Server< ActionT > >

Class Documentation

template<typename ActionT>
class Server : public rclcpp_action::ServerBase, public std::enable_shared_from_this<Server<ActionT>>

Action Server.

This class creates an action server.

Create an instance of this server using rclcpp_action::create_server().

Internally, this class is responsible for:

Public Types

using GoalCallback = std::function<GoalResponse(const GoalUUID&, std::shared_ptr<const typename ActionT::Goal>)>

Signature of a callback that accepts or rejects goal requests.

using CancelCallback = std::function<CancelResponse(std::shared_ptr<ServerGoalHandle<ActionT>>)>

Signature of a callback that accepts or rejects requests to cancel a goal.

using AcceptedCallback = std::function<void(std::shared_ptr<ServerGoalHandle<ActionT>>)>

Signature of a callback that is used to notify when the goal has been accepted.

Public Functions

inline Server(rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeClockInterface::SharedPtr node_clock, rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging, const std::string &name, const rcl_action_server_options_t &options, GoalCallback handle_goal, CancelCallback handle_cancel, AcceptedCallback handle_accepted)

Construct an action server.

This constructs an action server, but it will not work until it has been added to a node. Use rclcpp_action::create_server() to both construct and add to a node.

Three callbacks must be provided:

  • one to accept or reject goals sent to the server,

  • one to accept or reject requests to cancel a goal,

  • one to receive a goal handle after a goal has been accepted. All callbacks must be non-blocking. The result of a goal should be set using methods on rclcpp_action::ServerGoalHandle.

Parameters:
  • node_base[in] a pointer to the base interface of a node.

  • node_clock[in] a pointer to an interface that allows getting a node’s clock.

  • node_logging[in] a pointer to an interface that allows getting a node’s logger.

  • name[in] the name of an action. The same name and type must be used by both the action client and action server to communicate.

  • options[in] Options to pass to the underlying rcl_action_server_t.

  • handle_goal[in] a callback that decides if a goal should be accepted or rejected.

  • handle_cancel[in] a callback that decides if a goal should be attemted to be canceled. The return from this callback only indicates if the server will try to cancel a goal. It does not indicate if the goal was actually canceled.

  • handle_accepted[in] a callback that is called to give the user a handle to the goal. execution.

virtual ~Server() = default

Protected Functions

inline virtual std::pair<GoalResponse, std::shared_ptr<void>> call_handle_goal_callback(GoalUUID &uuid, std::shared_ptr<void> message) override
inline virtual CancelResponse call_handle_cancel_callback(const GoalUUID &uuid) override
inline virtual void call_goal_accepted_callback(std::shared_ptr<rcl_action_goal_handle_t> rcl_goal_handle, GoalUUID uuid, std::shared_ptr<void> goal_request_message) override

Call user callback to inform them a goal has been accepted.

inline virtual GoalUUID get_goal_id_from_goal_request(void *message) override

Given a goal request message, return the UUID contained within.

inline virtual std::shared_ptr<void> create_goal_request() override

Create an empty goal request message so it can be taken from a lower layer.

inline virtual GoalUUID get_goal_id_from_result_request(void *message) override

Given a result request message, return the UUID contained within.

inline virtual std::shared_ptr<void> create_result_request() override

Create an empty goal request message so it can be taken from a lower layer.

inline virtual std::shared_ptr<void> create_result_response(decltype(action_msgs::msg::GoalStatus::status) status) override

Create an empty goal result message so it can be sent as a reply in a lower layer