Skip to content

Commit b87740f

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

File tree

2 files changed

+150
-0
lines changed

2 files changed

+150
-0
lines changed

rmw_implementation/src/functions.cpp

+24
Original file line numberDiff line numberDiff line change
@@ -701,6 +701,26 @@ RMW_INTERFACE_FN(
701701
bool,
702702
rmw_topic_endpoint_info_array_t *))
703703

704+
RMW_INTERFACE_FN(
705+
rmw_get_clients_info_by_service,
706+
rmw_ret_t, RMW_RET_ERROR,
707+
5, ARG_TYPES(
708+
const rmw_node_t *,
709+
rcutils_allocator_t *,
710+
const char *,
711+
bool,
712+
rmw_topic_endpoint_info_array_t *))
713+
714+
RMW_INTERFACE_FN(
715+
rmw_get_servers_info_by_service,
716+
rmw_ret_t, RMW_RET_ERROR,
717+
5, ARG_TYPES(
718+
const rmw_node_t *,
719+
rcutils_allocator_t *,
720+
const char *,
721+
bool,
722+
rmw_topic_endpoint_info_array_t *))
723+
704724
RMW_INTERFACE_FN(
705725
rmw_qos_profile_check_compatible,
706726
rmw_ret_t, RMW_RET_ERROR,
@@ -868,6 +888,8 @@ void prefetch_symbols(void)
868888
GET_SYMBOL(rmw_set_log_severity)
869889
GET_SYMBOL(rmw_get_publishers_info_by_topic)
870890
GET_SYMBOL(rmw_get_subscriptions_info_by_topic)
891+
GET_SYMBOL(rmw_get_clients_info_by_service)
892+
GET_SYMBOL(rmw_get_servers_info_by_service)
871893
GET_SYMBOL(rmw_qos_profile_check_compatible)
872894
GET_SYMBOL(rmw_publisher_get_network_flow_endpoints)
873895
GET_SYMBOL(rmw_subscription_get_network_flow_endpoints)
@@ -990,6 +1012,8 @@ unload_library()
9901012
symbol_rmw_set_log_severity = nullptr;
9911013
symbol_rmw_get_publishers_info_by_topic = nullptr;
9921014
symbol_rmw_get_subscriptions_info_by_topic = nullptr;
1015+
symbol_rmw_get_clients_info_by_service = nullptr;
1016+
symbol_rmw_get_servers_info_by_service = nullptr;
9931017
symbol_rmw_qos_profile_check_compatible = nullptr;
9941018
symbol_rmw_publisher_get_network_flow_endpoints = nullptr;
9951019
symbol_rmw_subscription_get_network_flow_endpoints = nullptr;

test_rmw_implementation/test/test_graph_api.cpp

+126
Original file line numberDiff line numberDiff line change
@@ -833,6 +833,132 @@ TEST_F(TestGraphAPI, get_subscriptions_info_by_topic_with_bad_arguments) {
833833
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
834834
}
835835

836+
TEST_F(TestGraphAPI, get_clients_info_by_service_with_bad_arguments) {
837+
rcutils_allocator_t allocator = rcutils_get_default_allocator();
838+
constexpr char topic_name[] = "/test_service";
839+
bool no_mangle = false;
840+
rmw_topic_endpoint_info_array_t clients_info =
841+
rmw_get_zero_initialized_topic_endpoint_info_array();
842+
843+
// A null node is an invalid argument.
844+
rmw_ret_t ret = rmw_get_clients_info_by_service(
845+
nullptr, &allocator, topic_name, no_mangle, &clients_info);
846+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
847+
rmw_reset_error();
848+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
849+
850+
// A node from a different implementation is an invalid argument.
851+
const char * implementation_identifier = node->implementation_identifier;
852+
node->implementation_identifier = "not-an-rmw-implementation-identifier";
853+
ret = rmw_get_clients_info_by_service(
854+
node, &allocator, topic_name, no_mangle, &clients_info);
855+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
856+
node->implementation_identifier = implementation_identifier;
857+
rmw_reset_error();
858+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
859+
860+
// A null allocator is an invalid argument.
861+
ret = rmw_get_clients_info_by_service(
862+
node, nullptr, topic_name, no_mangle, &clients_info);
863+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
864+
rmw_reset_error();
865+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
866+
867+
// An invalid (zero initialized) allocator is an invalid argument.
868+
rcutils_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
869+
ret = rmw_get_clients_info_by_service(
870+
node, &invalid_allocator, topic_name, no_mangle, &clients_info);
871+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
872+
rmw_reset_error();
873+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
874+
875+
// A null topic name is an invalid argument.
876+
ret = rmw_get_clients_info_by_service(
877+
node, &allocator, nullptr, no_mangle, &clients_info);
878+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
879+
rmw_reset_error();
880+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
881+
882+
// A null array of topic endpoint info is an invalid argument.
883+
ret = rmw_get_clients_info_by_service(node, &allocator, topic_name, no_mangle, nullptr);
884+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
885+
rmw_reset_error();
886+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&clients_info));
887+
888+
// A non zero initialized array of topic endpoint info is an invalid argument.
889+
ret = rmw_topic_endpoint_info_array_init_with_size(&clients_info, 1u, &allocator);
890+
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
891+
ret = rmw_get_clients_info_by_service(
892+
node, &allocator, topic_name, no_mangle, &clients_info);
893+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
894+
rmw_reset_error();
895+
ret = rmw_topic_endpoint_info_array_fini(&clients_info, &allocator);
896+
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
897+
}
898+
899+
TEST_F(TestGraphAPI, get_servers_info_by_service_with_bad_arguments) {
900+
rcutils_allocator_t allocator = rcutils_get_default_allocator();
901+
constexpr char topic_name[] = "/test_service";
902+
bool no_mangle = false;
903+
rmw_topic_endpoint_info_array_t servers_info =
904+
rmw_get_zero_initialized_topic_endpoint_info_array();
905+
906+
// A null node is an invalid argument.
907+
rmw_ret_t ret = rmw_get_servers_info_by_service(
908+
nullptr, &allocator, topic_name, no_mangle, &servers_info);
909+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
910+
rmw_reset_error();
911+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
912+
913+
// A node from a different implementation is an invalid argument.
914+
const char * implementation_identifier = node->implementation_identifier;
915+
node->implementation_identifier = "not-an-rmw-implementation-identifier";
916+
ret = rmw_get_servers_info_by_service(
917+
node, &allocator, topic_name, no_mangle, &servers_info);
918+
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
919+
node->implementation_identifier = implementation_identifier;
920+
rmw_reset_error();
921+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
922+
923+
// A null allocator is an invalid argument.
924+
ret = rmw_get_servers_info_by_service(
925+
node, nullptr, topic_name, no_mangle, &servers_info);
926+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
927+
rmw_reset_error();
928+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
929+
930+
// An invalid (zero initialized) allocator is an invalid argument.
931+
rcutils_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
932+
ret = rmw_get_servers_info_by_service(
933+
node, &invalid_allocator, topic_name, no_mangle, &servers_info);
934+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
935+
rmw_reset_error();
936+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
937+
938+
// A null topic name is an invalid argument.
939+
ret = rmw_get_servers_info_by_service(
940+
node, &allocator, nullptr, no_mangle, &servers_info);
941+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
942+
rmw_reset_error();
943+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
944+
945+
// A null array of topic endpoint info is an invalid argument.
946+
ret = rmw_get_servers_info_by_service(node, &allocator, topic_name, no_mangle, nullptr);
947+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
948+
rmw_reset_error();
949+
EXPECT_EQ(RMW_RET_OK, rmw_topic_endpoint_info_array_check_zero(&servers_info));
950+
951+
// A non zero initialized array of topic endpoint info is an invalid argument.
952+
ret = rmw_topic_endpoint_info_array_init_with_size(&servers_info, 1u, &allocator);
953+
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
954+
ret = rmw_get_servers_info_by_service(
955+
node, &allocator, topic_name, no_mangle, &servers_info);
956+
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
957+
rmw_reset_error();
958+
ret = rmw_topic_endpoint_info_array_fini(&servers_info, &allocator);
959+
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
960+
}
961+
836962
TEST_F(TestGraphAPI, count_publishers_with_bad_arguments) {
837963
size_t count = 0u;
838964
constexpr char topic_name[] = "/test_topic";

0 commit comments

Comments
 (0)