Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
25 changes: 25 additions & 0 deletions rmw_implementation/src/functions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include "rmw/features.h"
#include "rmw/get_network_flow_endpoints.h"
#include "rmw/get_node_info_and_types.h"
#include "rmw/get_service_endpoint_info.h"
#include "rmw/get_service_names_and_types.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/get_topic_names_and_types.h"
Expand Down Expand Up @@ -701,6 +702,26 @@ RMW_INTERFACE_FN(
bool,
rmw_topic_endpoint_info_array_t *))

RMW_INTERFACE_FN(
rmw_get_clients_info_by_service,
rmw_ret_t, RMW_RET_ERROR,
5, ARG_TYPES(
const rmw_node_t *,
rcutils_allocator_t *,
const char *,
bool,
rmw_service_endpoint_info_array_t *))

RMW_INTERFACE_FN(
rmw_get_servers_info_by_service,
rmw_ret_t, RMW_RET_ERROR,
5, ARG_TYPES(
const rmw_node_t *,
rcutils_allocator_t *,
const char *,
bool,
rmw_service_endpoint_info_array_t *))

RMW_INTERFACE_FN(
rmw_qos_profile_check_compatible,
rmw_ret_t, RMW_RET_ERROR,
Expand Down Expand Up @@ -875,6 +896,8 @@ void prefetch_symbols(void)
GET_SYMBOL(rmw_set_log_severity)
GET_SYMBOL(rmw_get_publishers_info_by_topic)
GET_SYMBOL(rmw_get_subscriptions_info_by_topic)
GET_SYMBOL(rmw_get_clients_info_by_service)
GET_SYMBOL(rmw_get_servers_info_by_service)
GET_SYMBOL(rmw_qos_profile_check_compatible)
GET_SYMBOL(rmw_publisher_get_network_flow_endpoints)
GET_SYMBOL(rmw_subscription_get_network_flow_endpoints)
Expand Down Expand Up @@ -997,6 +1020,8 @@ unload_library()
symbol_rmw_set_log_severity = nullptr;
symbol_rmw_get_publishers_info_by_topic = nullptr;
symbol_rmw_get_subscriptions_info_by_topic = nullptr;
symbol_rmw_get_clients_info_by_service = nullptr;
symbol_rmw_get_servers_info_by_service = nullptr;
symbol_rmw_qos_profile_check_compatible = nullptr;
symbol_rmw_publisher_get_network_flow_endpoints = nullptr;
symbol_rmw_subscription_get_network_flow_endpoints = nullptr;
Expand Down
127 changes: 127 additions & 0 deletions test_rmw_implementation/test/test_graph_api.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

#include "rmw/error_handling.h"
#include "rmw/get_node_info_and_types.h"
#include "rmw/get_service_endpoint_info.h"
#include "rmw/get_service_names_and_types.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/get_topic_names_and_types.h"
Expand Down Expand Up @@ -835,6 +836,132 @@ TEST_F(TestGraphAPI, get_subscriptions_info_by_topic_with_bad_arguments) {
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(TestGraphAPI, get_clients_info_by_service_with_bad_arguments) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
constexpr char service_name[] = "/test_service";
bool no_mangle = false;
rmw_service_endpoint_info_array_t clients_info =
rmw_get_zero_initialized_service_endpoint_info_array();

// A null node is an invalid argument.
rmw_ret_t ret = rmw_get_clients_info_by_service(
nullptr, &allocator, service_name, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// A node from a different implementation is an invalid argument.
const char * implementation_identifier = node->implementation_identifier;
node->implementation_identifier = "not-an-rmw-implementation-identifier";
ret = rmw_get_clients_info_by_service(
node, &allocator, service_name, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
node->implementation_identifier = implementation_identifier;
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// A null allocator is an invalid argument.
ret = rmw_get_clients_info_by_service(
node, nullptr, service_name, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// An invalid (zero initialized) allocator is an invalid argument.
rcutils_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
ret = rmw_get_clients_info_by_service(
node, &invalid_allocator, service_name, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// A null service name is an invalid argument.
ret = rmw_get_clients_info_by_service(
node, &allocator, nullptr, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// A null array of service endpoint info is an invalid argument.
ret = rmw_get_clients_info_by_service(node, &allocator, service_name, no_mangle, nullptr);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&clients_info));

// A non zero initialized array of service endpoint info is an invalid argument.
ret = rmw_service_endpoint_info_array_init_with_size(&clients_info, 1u, &allocator);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
ret = rmw_get_clients_info_by_service(
node, &allocator, service_name, no_mangle, &clients_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
ret = rmw_service_endpoint_info_array_fini(&clients_info, &allocator);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(TestGraphAPI, get_servers_info_by_service_with_bad_arguments) {
rcutils_allocator_t allocator = rcutils_get_default_allocator();
constexpr char service_name[] = "/test_service";
bool no_mangle = false;
rmw_service_endpoint_info_array_t servers_info =
rmw_get_zero_initialized_service_endpoint_info_array();

// A null node is an invalid argument.
rmw_ret_t ret = rmw_get_servers_info_by_service(
nullptr, &allocator, service_name, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// A node from a different implementation is an invalid argument.
const char * implementation_identifier = node->implementation_identifier;
node->implementation_identifier = "not-an-rmw-implementation-identifier";
ret = rmw_get_servers_info_by_service(
node, &allocator, service_name, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INCORRECT_RMW_IMPLEMENTATION, ret);
node->implementation_identifier = implementation_identifier;
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// A null allocator is an invalid argument.
ret = rmw_get_servers_info_by_service(
node, nullptr, service_name, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// An invalid (zero initialized) allocator is an invalid argument.
rcutils_allocator_t invalid_allocator = rcutils_get_zero_initialized_allocator();
ret = rmw_get_servers_info_by_service(
node, &invalid_allocator, service_name, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// A null service name is an invalid argument.
ret = rmw_get_servers_info_by_service(
node, &allocator, nullptr, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// A null array of service endpoint info is an invalid argument.
ret = rmw_get_servers_info_by_service(node, &allocator, service_name, no_mangle, nullptr);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
EXPECT_EQ(RMW_RET_OK, rmw_service_endpoint_info_array_check_zero(&servers_info));

// A non zero initialized array of service endpoint info is an invalid argument.
ret = rmw_service_endpoint_info_array_init_with_size(&servers_info, 1u, &allocator);
ASSERT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
ret = rmw_get_servers_info_by_service(
node, &allocator, service_name, no_mangle, &servers_info);
EXPECT_EQ(RMW_RET_INVALID_ARGUMENT, ret);
rmw_reset_error();
ret = rmw_service_endpoint_info_array_fini(&servers_info, &allocator);
EXPECT_EQ(RMW_RET_OK, ret) << rmw_get_error_string().str;
}

TEST_F(TestGraphAPI, count_publishers_with_bad_arguments) {
size_t count = 0u;
constexpr char topic_name[] = "/test_topic";
Expand Down