Skip to content

Commit f0957db

Browse files
committed
add: get clients, servers info
Signed-off-by: Minju, Lee <[email protected]>
1 parent 34c59bf commit f0957db

File tree

3 files changed

+446
-0
lines changed

3 files changed

+446
-0
lines changed

rcl/include/rcl/graph.h

Lines changed: 122 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -971,6 +971,128 @@ rcl_get_subscriptions_info_by_topic(
971971
bool no_mangle,
972972
rcl_topic_endpoint_info_array_t * subscriptions_info);
973973

974+
/// Return a list of all clients to a service.
975+
/**
976+
* The `node` parameter must point to a valid node.
977+
*
978+
* The `service_name` parameter must not be `NULL`.
979+
*
980+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid name
981+
* for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps).
982+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
983+
* ROS topic name conventions.
984+
* In either case, the service name should always be fully qualified.
985+
*
986+
* Each element in the `clients_info` array will contain the node name, node namespace,
987+
* service type, gid and the qos profile of the client.
988+
* It is the responsibility of the caller to ensure that `clients_info` parameter points
989+
* to a valid struct of type rcl_topic_endpoint_info_array_t.
990+
* The `count` field inside the struct must be set to 0 and the `info_array` field inside
991+
* the struct must be set to null.
992+
* \see rmw_get_zero_initialized_topic_endpoint_info_array
993+
*
994+
* The `allocator` will be used to allocate memory to the `info_array` member
995+
* inside of `clients_info`.
996+
* Moreover, every const char * member inside of
997+
* rmw_topic_endpoint_info_t will be assigned a copied value on allocated memory.
998+
* \see rmw_topic_endpoint_info_set_node_name and the likes.
999+
* However, it is the responsibility of the caller to
1000+
* reclaim any allocated resources to `clients_info` to avoid leaking memory.
1001+
* \see rmw_topic_endpoint_info_array_fini
1002+
*
1003+
* <hr>
1004+
* Attribute | Adherence
1005+
* ------------------ | -------------
1006+
* Allocates Memory | Yes
1007+
* Thread-Safe | No
1008+
* Uses Atomics | No
1009+
* Lock-Free | Maybe [1]
1010+
* <i>[1] implementation may need to protect the data structure with a lock</i>
1011+
*
1012+
* \param[in] node the handle to the node being used to query the ROS graph
1013+
* \param[in] allocator allocator to be used when allocating space for
1014+
* the array inside clients_info
1015+
* \param[in] service_name the name of the service in question
1016+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware topic name,
1017+
* otherwise it should be a valid ROS topic name
1018+
* \param[out] clients_info a struct representing a list of client information
1019+
* \return #RCL_RET_OK if the query was successful, or
1020+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
1021+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
1022+
* \return #RCL_RET_BAD_ALLOC if memory allocation fails, or
1023+
* \return #RCL_RET_ERROR if an unspecified error occurs.
1024+
*/
1025+
RCL_PUBLIC
1026+
RCL_WARN_UNUSED
1027+
rcl_ret_t
1028+
rcl_get_clients_info_by_service(
1029+
const rcl_node_t * node,
1030+
rcutils_allocator_t * allocator,
1031+
const char * service_name,
1032+
bool no_mangle,
1033+
rcl_topic_endpoint_info_array_t * clients_info);
1034+
1035+
/// Return a list of all servers to a service.
1036+
/**
1037+
* The `node` parameter must point to a valid node.
1038+
*
1039+
* The `service_name` parameter must not be `NULL`.
1040+
*
1041+
* When the `no_mangle` parameter is `true`, the provided `service_name` should be a valid name
1042+
* for the middleware (useful when combining ROS with native middleware (e.g. DDS) apps).
1043+
* When the `no_mangle` parameter is `false`, the provided `service_name` should follow
1044+
* ROS topic name conventions.
1045+
* In either case, the service name should always be fully qualified.
1046+
*
1047+
* Each element in the `servers_info` array will contain the node name, node namespace,
1048+
* service type, gid and the qos profile of the server.
1049+
* It is the responsibility of the caller to ensure that `servers_info` parameter points
1050+
* to a valid struct of type rcl_topic_endpoint_info_array_t.
1051+
* The `count` field inside the struct must be set to 0 and the `info_array` field inside
1052+
* the struct must be set to null.
1053+
* \see rmw_get_zero_initialized_topic_endpoint_info_array
1054+
*
1055+
* The `allocator` will be used to allocate memory to the `info_array` member
1056+
* inside of `servers_info`.
1057+
* Moreover, every const char * member inside of
1058+
* rmw_topic_endpoint_info_t will be assigned a copied value on allocated memory.
1059+
* \see rmw_topic_endpoint_info_set_node_name and the likes.
1060+
* However, it is the responsibility of the caller to
1061+
* reclaim any allocated resources to `servers_info` to avoid leaking memory.
1062+
* \see rmw_topic_endpoint_info_array_fini
1063+
*
1064+
* <hr>
1065+
* Attribute | Adherence
1066+
* ------------------ | -------------
1067+
* Allocates Memory | Yes
1068+
* Thread-Safe | No
1069+
* Uses Atomics | No
1070+
* Lock-Free | Maybe [1]
1071+
* <i>[1] implementation may need to protect the data structure with a lock</i>
1072+
*
1073+
* \param[in] node the handle to the node being used to query the ROS graph
1074+
* \param[in] allocator allocator to be used when allocating space for
1075+
* the array inside clients_info
1076+
* \param[in] service_name the name of the service in question
1077+
* \param[in] no_mangle if `true`, `service_name` needs to be a valid middleware topic name,
1078+
* otherwise it should be a valid ROS topic name
1079+
* \param[out] servers_info a struct representing a list of server information
1080+
* \return #RCL_RET_OK if the query was successful, or
1081+
* \return #RCL_RET_NODE_INVALID if the node is invalid, or
1082+
* \return #RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
1083+
* \return #RCL_RET_BAD_ALLOC if memory allocation fails, or
1084+
* \return #RCL_RET_ERROR if an unspecified error occurs.
1085+
*/
1086+
RCL_PUBLIC
1087+
RCL_WARN_UNUSED
1088+
rcl_ret_t
1089+
rcl_get_servers_info_by_service(
1090+
const rcl_node_t * node,
1091+
rcutils_allocator_t * allocator,
1092+
const char * service_name,
1093+
bool no_mangle,
1094+
rcl_topic_endpoint_info_array_t * servers_info);
1095+
9741096
/// Check if a service server is available for the given service client.
9751097
/**
9761098
* This function will return true for `is_available` if there is a service server

rcl/src/rcl/graph.c

Lines changed: 34 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -789,6 +789,40 @@ rcl_get_subscriptions_info_by_topic(
789789
rmw_get_subscriptions_info_by_topic);
790790
}
791791

792+
rcl_ret_t
793+
rcl_get_clients_info_by_service(
794+
const rcl_node_t * node,
795+
rcutils_allocator_t * allocator,
796+
const char * service_name,
797+
bool no_mangle,
798+
rmw_topic_endpoint_info_array_t * clients_info)
799+
{
800+
return __rcl_get_info_by_topic(
801+
node,
802+
allocator,
803+
service_name,
804+
no_mangle,
805+
clients_info,
806+
rmw_get_clients_info_by_service);
807+
}
808+
809+
rcl_ret_t
810+
rcl_get_servers_info_by_service(
811+
const rcl_node_t * node,
812+
rcutils_allocator_t * allocator,
813+
const char * service_name,
814+
bool no_mangle,
815+
rmw_topic_endpoint_info_array_t * servers_info)
816+
{
817+
return __rcl_get_info_by_topic(
818+
node,
819+
allocator,
820+
service_name,
821+
no_mangle,
822+
servers_info,
823+
rmw_get_servers_info_by_service);
824+
}
825+
792826
rcl_ret_t
793827
rcl_service_server_is_available(
794828
const rcl_node_t * node,

0 commit comments

Comments
 (0)