Skip to content

Commit 03fd83d

Browse files
committed
Introduce client and server info by service
Signed-off-by: Minju, Lee <[email protected]>
1 parent b4f0c4c commit 03fd83d

File tree

5 files changed

+854
-0
lines changed

5 files changed

+854
-0
lines changed

rcl/include/rcl/graph.h

Lines changed: 220 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -24,6 +24,7 @@ extern "C"
2424

2525
#include <rmw/names_and_types.h>
2626
#include <rmw/get_topic_names_and_types.h>
27+
#include <rmw/service_endpoint_info_array.h>
2728
#include <rmw/topic_endpoint_info_array.h>
2829

2930
#include "rcutils/time.h"
@@ -47,6 +48,14 @@ typedef rmw_topic_endpoint_info_t rcl_topic_endpoint_info_t;
4748
/// An array of topic endpoint information.
4849
typedef rmw_topic_endpoint_info_array_t rcl_topic_endpoint_info_array_t;
4950

51+
/// A structure that encapsulates the node name, node namespace,
52+
/// service type, gids, and qos_profiles or clients and servers
53+
/// for a service.
54+
typedef rmw_service_endpoint_info_t rcl_service_endpoint_info_t;
55+
56+
// An array of service endpoint information.
57+
typedef rmw_service_endpoint_info_array_t rcl_service_endpoint_info_array_t;
58+
5059
/// Return a zero-initialized rcl_names_and_types_t structure.
5160
#define rcl_get_zero_initialized_names_and_types rmw_get_zero_initialized_names_and_types
5261

@@ -57,6 +66,13 @@ typedef rmw_topic_endpoint_info_array_t rcl_topic_endpoint_info_array_t;
5766
/// Finalize a topic_endpoint_info_array_t structure.
5867
#define rcl_topic_endpoint_info_array_fini rmw_topic_endpoint_info_array_fini
5968

69+
/// Return a zero-initialized rcl_service_endpoint_info_t structure.
70+
#define rcl_get_zero_initialized_service_endpoint_info_array \
71+
rmw_get_zero_initialized_service_endpoint_info_array
72+
73+
/// Finalize a service_endpoint_info_array_t structure.
74+
#define rcl_service_endpoint_info_array_fini rmw_service_endpoint_info_array_fini
75+
6076
/// Return a list of topic names and types for publishers associated with a node.
6177
/**
6278
* The `node` parameter must point to a valid node.
@@ -775,6 +791,80 @@ rcl_wait_for_subscribers(
775791
rcutils_duration_value_t timeout,
776792
bool * success);
777793

794+
/// Wait for there to be a specified number of clients on a given service.
795+
/**
796+
* \see rcl_wait_for_publishers
797+
*
798+
* <hr>
799+
* Attribute | Adherence
800+
* ------------------ | -------------
801+
* Allocates Memory | Yes
802+
* Thread-Safe | No
803+
* Uses Atomics | No
804+
* Lock-Free | Maybe [1]
805+
* <i>[1] implementation may need to protect the data structure with a lock</i>
806+
*
807+
* \param[in] node the handle to the node being used to query the ROS graph
808+
* \param[in] allocator to allocate space for the rcl_wait_set_t used to wait for graph events
809+
* \param[in] service_name the name of the service in question
810+
* \param[in] count number of clients to wait for
811+
* \param[in] timeout maximum duration to wait for clients
812+
* \param[out] success `true` if the number of clients is equal to or greater than count, or
813+
* `false` if a timeout occurred waiting for clients.
814+
* \return #RCL_RET_OK if there was no errors, or
815+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
816+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
817+
* \return #RCL_RET_TIMEOUT if a timeout occurs before the number of clients is detected, or
818+
* \return #RCL_RET_ERROR if an unspecified error occurred.
819+
*/
820+
RCL_PUBLIC
821+
RCL_WARN_UNUSED
822+
rcl_ret_t
823+
rcl_wait_for_clients(
824+
const rcl_node_t * node,
825+
rcl_allocator_t * allocator,
826+
const char * service_name,
827+
const size_t count,
828+
rcutils_duration_value_t timeout,
829+
bool * success);
830+
831+
/// Wait for there to be a specified number of servers on a given service.
832+
/**
833+
* \see rcl_wait_for_publishers
834+
*
835+
* <hr>
836+
* Attribute | Adherence
837+
* ------------------ | -------------
838+
* Allocates Memory | Yes
839+
* Thread-Safe | No
840+
* Uses Atomics | No
841+
* Lock-Free | Maybe [1]
842+
* <i>[1] implementation may need to protect the data structure with a lock</i>
843+
*
844+
* \param[in] node the handle to the node being used to query the ROS graph
845+
* \param[in] allocator to allocate space for the rcl_wait_set_t used to wait for graph events
846+
* \param[in] service_name the name of the service in question
847+
* \param[in] count number of servers to wait for
848+
* \param[in] timeout maximum duration to wait for servers
849+
* \param[out] success `true` if the number of servers is equal to or greater than count, or
850+
* `false` if a timeout occurred waiting for servers.
851+
* \return #RCL_RET_OK if there was no errors, or
852+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
853+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
854+
* \return #RCL_RET_TIMEOUT if a timeout occurs before the number of servers is detected, or
855+
* \return #RCL_RET_ERROR if an unspecified error occurred.
856+
*/
857+
RCL_PUBLIC
858+
RCL_WARN_UNUSED
859+
rcl_ret_t
860+
rcl_wait_for_servers(
861+
const rcl_node_t * node,
862+
rcl_allocator_t * allocator,
863+
const char * service_name,
864+
const size_t count,
865+
rcutils_duration_value_t timeout,
866+
bool * success);
867+
778868
/// Return a list of all publishers to a topic.
779869
/**
780870
* The `node` parameter must point to a valid node.
@@ -897,6 +987,136 @@ rcl_get_subscriptions_info_by_topic(
897987
bool no_mangle,
898988
rcl_topic_endpoint_info_array_t * subscriptions_info);
899989

990+
/// Return a list of all clients to a service.
991+
/**
992+
* The `node` parameter must point to a valid node.
993+
*
994+
* The `service_name` parameter must not be `NULL`.
995+
*
996+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid name
997+
* for the middleware (useful when combining ROS with native middleware apps).
998+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
999+
* ROS service name conventions. In DDS-based RMWs, services are implemented as topics with mangled
1000+
* names (e.g., `rq/my_serviceRequest` and `rp/my_serviceReply`), so `no_mangle = true` is not
1001+
* supported and will result in an error. Use `rcl_get_publishers_info_by_topic` or
1002+
* `rcl_get_subscriptions_info_by_topic` for unmangled topic queries in such cases. Other RMWs
1003+
* (e.g., Zenoh) may support `no_mangle = true` if they natively handle services without topic-based
1004+
* mangling. In either case, the service name should always be fully qualified.
1005+
*
1006+
* Each element in the `clients_info` array will contain the node name, node namespace,
1007+
* service type, endpoint_count, gids and the qos profiles of the client.
1008+
* It is the responsibility of the caller to ensure that `clients_info` parameter points
1009+
* to a valid struct of type rcl_service_endpoint_info_array_t.
1010+
* The `count` field inside the struct must be set to 0 and the `info_array` field inside
1011+
* the struct must be set to null.
1012+
* \see rmw_get_zero_initialized_service_endpoint_info_array
1013+
*
1014+
* The `allocator` will be used to allocate memory to the `info_array` member
1015+
* inside of `clients_info`.
1016+
* Moreover, every const char * member inside of
1017+
* rmw_service_endpoint_info_t will be assigned a copied value on allocated memory.
1018+
* \see rmw_service_endpoint_info_set_node_name and the likes.
1019+
* However, it is the responsibility of the caller to
1020+
* reclaim any allocated resources to `clients_info` to avoid leaking memory.
1021+
* \see rmw_service_endpoint_info_array_fini
1022+
*
1023+
* <hr>
1024+
* Attribute | Adherence
1025+
* ------------------ | -------------
1026+
* Allocates Memory | Yes
1027+
* Thread-Safe | No
1028+
* Uses Atomics | No
1029+
* Lock-Free | Maybe [1]
1030+
* <i>[1] implementation may need to protect the data structure with a lock</i>
1031+
*
1032+
* \param[in] node the handle to the node being used to query the ROS graph
1033+
* \param[in] allocator allocator to be used when allocating space for
1034+
* the array inside clients_info
1035+
* \param[in] service_name the name of the service in question
1036+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
1037+
* otherwise it should be a valid ROS service name
1038+
* \param[out] clients_info a struct representing a list of client information
1039+
* \return #RCL_RET_OK if the query was successful, or
1040+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
1041+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
1042+
* \return #RCL_RET_BAD_ALLOC if memory allocation fails, or
1043+
* \return #RCL_RET_ERROR if an unspecified error occurs.
1044+
*/
1045+
RCL_PUBLIC
1046+
RCL_WARN_UNUSED
1047+
rcl_ret_t
1048+
rcl_get_clients_info_by_service(
1049+
const rcl_node_t * node,
1050+
rcutils_allocator_t * allocator,
1051+
const char * service_name,
1052+
bool no_mangle,
1053+
rcl_service_endpoint_info_array_t * clients_info);
1054+
1055+
/// Return a list of all servers to a service.
1056+
/**
1057+
* The `node` parameter must point to a valid node.
1058+
*
1059+
* The `service_name` parameter must not be `NULL`.
1060+
*
1061+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid name
1062+
* for the middleware (useful when combining ROS with native middleware apps).
1063+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
1064+
* ROS service name conventions. In DDS-based RMWs, services are implemented as topics with mangled
1065+
* names (e.g., `rq/my_serviceRequest` and `rp/my_serviceReply`), so `no_mangle = true` is not
1066+
* supported and will result in an error. Use `rcl_get_publishers_info_by_topic` or
1067+
* `rcl_get_subscriptions_info_by_topic` for unmangled topic queries in such cases. Other RMWs
1068+
* (e.g., Zenoh) may support `no_mangle = true` if they natively handle services without topic-based
1069+
* mangling. In either case, the service name should always be fully qualified.
1070+
*
1071+
* Each element in the `servers_info` array will contain the node name, node namespace,
1072+
* service type, endpoint_count, gid and the qos profile of the server.
1073+
* It is the responsibility of the caller to ensure that `servers_info` parameter points
1074+
* to a valid struct of type rcl_service_endpoint_info_array_t.
1075+
* The `count` field inside the struct must be set to 0 and the `info_array` field inside
1076+
* the struct must be set to null.
1077+
* \see rmw_get_zero_initialized_service_endpoint_info_array
1078+
*
1079+
* The `allocator` will be used to allocate memory to the `info_array` member
1080+
* inside of `servers_info`.
1081+
* Moreover, every const char * member inside of
1082+
* rmw_service_endpoint_info_t will be assigned a copied value on allocated memory.
1083+
* \see rmw_service_endpoint_info_set_node_name and the likes.
1084+
* However, it is the responsibility of the caller to
1085+
* reclaim any allocated resources to `servers_info` to avoid leaking memory.
1086+
* \see rmw_service_endpoint_info_array_fini
1087+
*
1088+
* <hr>
1089+
* Attribute | Adherence
1090+
* ------------------ | -------------
1091+
* Allocates Memory | Yes
1092+
* Thread-Safe | No
1093+
* Uses Atomics | No
1094+
* Lock-Free | Maybe [1]
1095+
* <i>[1] implementation may need to protect the data structure with a lock</i>
1096+
*
1097+
* \param[in] node the handle to the node being used to query the ROS graph
1098+
* \param[in] allocator allocator to be used when allocating space for
1099+
* the array inside clients_info
1100+
* \param[in] service_name the name of the service in question
1101+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware service name,
1102+
* otherwise it should be a valid ROS service name
1103+
* \param[out] servers_info a struct representing a list of server information
1104+
* \return #RCL_RET_OK if the query was successful, or
1105+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
1106+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
1107+
* \return #RCL_RET_BAD_ALLOC if memory allocation fails, or
1108+
* \return #RCL_RET_ERROR if an unspecified error occurs.
1109+
*/
1110+
RCL_PUBLIC
1111+
RCL_WARN_UNUSED
1112+
rcl_ret_t
1113+
rcl_get_servers_info_by_service(
1114+
const rcl_node_t * node,
1115+
rcutils_allocator_t * allocator,
1116+
const char * service_name,
1117+
bool no_mangle,
1118+
rcl_service_endpoint_info_array_t * servers_info);
1119+
9001120
/// Check if a service server is available for the given service client.
9011121
/**
9021122
* This function will return true for `is_available` if there is a service server

0 commit comments

Comments
 (0)