Skip to content

Commit a02b681

Browse files
committed
Add rmw_get_clients_info_by_service , rmw_servers_clients_info_by_service
Signed-off-by: Minju, Lee <[email protected]>
1 parent 8c00608 commit a02b681

File tree

2 files changed

+152
-0
lines changed

2 files changed

+152
-0
lines changed

rmw_implementation/src/functions.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#include "rmw/features.h"
3535
#include "rmw/get_network_flow_endpoints.h"
3636
#include "rmw/get_node_info_and_types.h"
37+
#include "rmw/get_service_endpoint_info.h"
3738
#include "rmw/get_service_names_and_types.h"
3839
#include "rmw/get_topic_endpoint_info.h"
3940
#include "rmw/get_topic_names_and_types.h"
@@ -701,6 +702,26 @@ RMW_INTERFACE_FN(
701702
bool,
702703
rmw_topic_endpoint_info_array_t *))
703704

705+
RMW_INTERFACE_FN(
706+
rmw_get_clients_info_by_service,
707+
rmw_ret_t, RMW_RET_ERROR,
708+
5, ARG_TYPES(
709+
const rmw_node_t *,
710+
rcutils_allocator_t *,
711+
const char *,
712+
bool,
713+
rmw_service_endpoint_info_array_t *))
714+
715+
RMW_INTERFACE_FN(
716+
rmw_get_servers_info_by_service,
717+
rmw_ret_t, RMW_RET_ERROR,
718+
5, ARG_TYPES(
719+
const rmw_node_t *,
720+
rcutils_allocator_t *,
721+
const char *,
722+
bool,
723+
rmw_service_endpoint_info_array_t *))
724+
704725
RMW_INTERFACE_FN(
705726
rmw_qos_profile_check_compatible,
706727
rmw_ret_t, RMW_RET_ERROR,
@@ -875,6 +896,8 @@ void prefetch_symbols(void)
875896
GET_SYMBOL(rmw_set_log_severity)
876897
GET_SYMBOL(rmw_get_publishers_info_by_topic)
877898
GET_SYMBOL(rmw_get_subscriptions_info_by_topic)
899+
GET_SYMBOL(rmw_get_clients_info_by_service)
900+
GET_SYMBOL(rmw_get_servers_info_by_service)
878901
GET_SYMBOL(rmw_qos_profile_check_compatible)
879902
GET_SYMBOL(rmw_publisher_get_network_flow_endpoints)
880903
GET_SYMBOL(rmw_subscription_get_network_flow_endpoints)
@@ -997,6 +1020,8 @@ unload_library()
9971020
symbol_rmw_set_log_severity = nullptr;
9981021
symbol_rmw_get_publishers_info_by_topic = nullptr;
9991022
symbol_rmw_get_subscriptions_info_by_topic = nullptr;
1023+
symbol_rmw_get_clients_info_by_service = nullptr;
1024+
symbol_rmw_get_servers_info_by_service = nullptr;
10001025
symbol_rmw_qos_profile_check_compatible = nullptr;
10011026
symbol_rmw_publisher_get_network_flow_endpoints = nullptr;
10021027
symbol_rmw_subscription_get_network_flow_endpoints = nullptr;

test_rmw_implementation/test/test_graph_api.cpp

Lines changed: 127 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121

2222
#include "rmw/error_handling.h"
2323
#include "rmw/get_node_info_and_types.h"
24+
#include "rmw/get_service_endpoint_info.h"
2425
#include "rmw/get_service_names_and_types.h"
2526
#include "rmw/get_topic_endpoint_info.h"
2627
#include "rmw/get_topic_names_and_types.h"
@@ -835,6 +836,132 @@ TEST_F(TestGraphAPI, get_subscriptions_info_by_topic_with_bad_arguments) {
835836
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
836837
}
837838

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

0 commit comments

Comments
 (0)