Class ServerBase

Inheritance Relationships

Base Type

  • public rclcpp::Waitable

Derived Type

Class Documentation

class ServerBase : public rclcpp::Waitable

Base Action Server implementation This class should not be used directly by users writing an action server. Instead users should use rclcpp_action::Server.

Internally, this class is responsible for interfacing with the rcl_action API.

Subclassed by rclcpp_action::Server< ActionT >

Public Types

enum class EntityType : std::size_t

Enum to identify entities belonging to the action server.

Values:

enumerator GoalService
enumerator ResultService
enumerator CancelService

Public Functions

virtual ~ServerBase()
virtual size_t get_number_of_ready_subscriptions() override

Return the number of subscriptions used to implement an action server

virtual size_t get_number_of_ready_timers() override

Return the number of timers used to implement an action server

virtual size_t get_number_of_ready_clients() override

Return the number of service clients used to implement an action server

virtual size_t get_number_of_ready_services() override

Return the number of service servers used to implement an action server

virtual size_t get_number_of_ready_guard_conditions() override

Return the number of guard conditions used to implement an action server

virtual void add_to_wait_set(rcl_wait_set_t *wait_set) override

Add all entities to a wait set.

virtual bool is_ready(rcl_wait_set_t*) override

Return true if any entity belonging to the action server is ready to be executed.

virtual std::shared_ptr<void> take_data() override
virtual std::shared_ptr<void> take_data_by_entity_id(size_t id) override
virtual void execute(std::shared_ptr<void> &data) override

Act on entities in the wait set which are ready to be acted upon.

virtual void set_on_ready_callback(std::function<void(size_t, int)> callback) override

The callback receives a size_t which is the number of messages received since the last time this callback was called. Normally this is 1, but can be > 1 if messages were received before any callback was set.

The callback also receives an int identifier argument, which identifies the action server entity which is ready. This implies that the provided callback can use the identifier to behave differently depending on which entity triggered the waitable to become ready.

Calling it again will clear any previously set callback.

An exception will be thrown if the callback is not callable.

This function is thread-safe.

If you want more information available in the callback, like the subscription or other information, you may use a lambda with captures or std::bind.

Parameters:

callback[in] functor to be called when a new message is received.

virtual void clear_on_ready_callback() override

Unset the callback to be called whenever the waitable becomes ready.

Protected Functions

ServerBase(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 rosidl_action_type_support_t *type_support, const rcl_action_server_options_t &options)
virtual std::pair<GoalResponse, std::shared_ptr<void>> call_handle_goal_callback(GoalUUID&, std::shared_ptr<void> request) = 0
virtual CancelResponse call_handle_cancel_callback(const GoalUUID &uuid) = 0
virtual GoalUUID get_goal_id_from_goal_request(void *message) = 0

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

virtual std::shared_ptr<void> create_goal_request() = 0

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

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) = 0

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

virtual GoalUUID get_goal_id_from_result_request(void *message) = 0

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

virtual std::shared_ptr<void> create_result_request() = 0

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

virtual std::shared_ptr<void> create_result_response(decltype(action_msgs::msg::GoalStatus::status) status) = 0

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

void publish_status()
void notify_goal_terminal_state()
void publish_result(const GoalUUID &uuid, std::shared_ptr<void> result_msg)
void publish_feedback(std::shared_ptr<void> feedback_msg)
void set_on_ready_callback(EntityType entity_type, rcl_event_callback_t callback, const void *user_data)

Set a callback to be called when the specified entity is ready.

Protected Attributes

std::recursive_mutex listener_mutex_
std::unordered_map<EntityType, std::function<void(size_t)>> entity_type_to_on_ready_callback_
bool on_ready_callback_set_ = {false}