Class ServiceEndpointInfo

Class Documentation

class ServiceEndpointInfo

Struct that contains service endpoint information like the associated node name, node namespace, service type, endpoint type, endpoint count, endpoint GIDs, and its QoS profiles.

Public Functions

inline explicit ServiceEndpointInfo(const rcl_service_endpoint_info_t &info)

Construct a ServiceEndpointInfo from a rcl_service_endpoint_info_t.

std::string &node_name()

Get a mutable reference to the node name.

const std::string &node_name() const

Get a const reference to the node name.

std::string &node_namespace()

Get a mutable reference to the node namespace.

const std::string &node_namespace() const

Get a const reference to the node namespace.

std::string &service_type()

Get a mutable reference to the service type string.

const std::string &service_type() const

Get a const reference to the service type string.

rclcpp::EndpointType &endpoint_type()

Get a mutable reference to the service endpoint type.

const rclcpp::EndpointType &endpoint_type() const

Get a const reference to the service endpoint type.

size_t &endpoint_count()

Get a mutable reference to the endpoint count.

const size_t &endpoint_count() const

Get a const reference to the endpoint count.

std::vector<std::array<uint8_t, RMW_GID_STORAGE_SIZE>> &endpoint_gids()

Get a mutable reference to the GID of the service endpoint.

const std::vector<std::array<uint8_t, RMW_GID_STORAGE_SIZE>> &endpoint_gids() const

Get a const reference to the GID of the service endpoint.

std::vector<rclcpp::QoS> &qos_profiles()

Get a mutable reference to the QoS profile of the service endpoint.

const std::vector<rclcpp::QoS> &qos_profiles() const

Get a const reference to the QoS profile of the service endpoint.

rosidl_type_hash_t &service_type_hash()

Get a mutable reference to the type hash of the service endpoint.

const rosidl_type_hash_t &service_type_hash() const

Get a const reference to the type hash of the service endpoint.