diff --git a/rcl/include/rcl/graph.h b/rcl/include/rcl/graph.h index d68c025d4..84b855c14 100644 --- a/rcl/include/rcl/graph.h +++ b/rcl/include/rcl/graph.h @@ -135,7 +135,7 @@ rcl_get_subscriber_names_and_types_by_node( const char * node_namespace, rcl_names_and_types_t * topic_names_and_types); -/// Return a list of service names and types for associated with a node. +/// Return a list of service names and types associated with a node. /** * The `node` parameter must point to a valid node. * @@ -148,7 +148,7 @@ rcl_get_subscriber_names_and_types_by_node( * \see rcl_get_publisher_names_and_types_by_node for details on the `no_demangle` parameter. * * The returned names are not automatically remapped by this function. - * Attempting to create clients or services using names returned by this function may not + * Attempting to create service clients using names returned by this function may not * result in the desired service name being used depending on the remap rules in use. * *
@@ -180,6 +180,51 @@ rcl_get_service_names_and_types_by_node( const char * node_namespace, rcl_names_and_types_t * service_names_and_types); +/// Return a list of service client names and types associated with a node. +/** + * The `node` parameter must point to a valid node. + * + * The `service_names_and_types` parameter must be allocated and zero initialized. + * This function allocates memory for the returned list of names and types and so it is the + * callers responsibility to pass `service_names_and_types` to rcl_names_and_types_fini() + * when it is no longer needed. + * Failing to do so will result in leaked memory. + * + * \see rcl_get_publisher_names_and_types_by_node for details on the `no_demangle` parameter. + * + * The returned names are not automatically remapped by this function. + * Attempting to create service servers using names returned by this function may not + * result in the desired service name being used depending on the remap rules in use. + * + *
+ * Attribute | Adherence + * ------------------ | ------------- + * Allocates Memory | Yes + * Thread-Safe | No + * Uses Atomics | No + * Lock-Free | Maybe [1] + * [1] implementation may need to protect the data structure with a lock + * + * \param[in] node the handle to the node being used to query the ROS graph + * \param[in] allocator allocator to be used when allocating space for strings + * \param[in] node_name the node name of the services to return + * \param[in] node_namespace the node namespace of the services to return + * \param[out] service_names_and_types list of service client names and their types + * \return `RCL_RET_OK` if the query was successful, or + * \return `RCL_RET_NODE_INVALID` if the node is invalid, or + * \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or + * \return `RCL_RET_ERROR` if an unspecified error occurs. + */ +RCL_PUBLIC +RCL_WARN_UNUSED +rcl_ret_t +rcl_get_client_names_and_types_by_node( + const rcl_node_t * node, + rcl_allocator_t * allocator, + const char * node_name, + const char * node_namespace, + rcl_names_and_types_t * service_names_and_types); + /// Return a list of topic names and their types. /** * The `node` parameter must point to a valid node. diff --git a/rcl/src/rcl/graph.c b/rcl/src/rcl/graph.c index f16efe4db..c43722775 100644 --- a/rcl/src/rcl/graph.c +++ b/rcl/src/rcl/graph.c @@ -142,6 +142,42 @@ rcl_get_service_names_and_types_by_node( return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); } +rcl_ret_t +rcl_get_client_names_and_types_by_node( + const rcl_node_t * node, + rcl_allocator_t * allocator, + const char * node_name, + const char * node_namespace, + rcl_names_and_types_t * service_names_and_types) +{ + if (!rcl_node_is_valid(node)) { + return RCL_RET_NODE_INVALID; + } + RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(node_name, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(node_namespace, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT); + + const char * valid_namespace = "/"; + if (strlen(node_namespace) > 0) { + valid_namespace = node_namespace; + } + rmw_ret_t rmw_ret; + rmw_ret = rmw_names_and_types_check_zero(service_names_and_types); + if (rmw_ret != RMW_RET_OK) { + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); + } + rcutils_allocator_t rcutils_allocator = *allocator; + rmw_ret = rmw_get_client_names_and_types_by_node( + rcl_node_get_rmw_handle(node), + &rcutils_allocator, + node_name, + valid_namespace, + service_names_and_types + ); + return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); +} + rcl_ret_t rcl_get_topic_names_and_types( const rcl_node_t * node, diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 90381e0ea..2a6bd1e76 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -516,6 +516,78 @@ TEST_F( rcl_reset_error(); } +/* Test the rcl_get_client_names_and_types_by_node function. + * + * This does not test content of the response. + */ +TEST_F( + CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), + test_rcl_get_client_names_and_types_by_node +) { + rcl_ret_t ret; + rcl_allocator_t allocator = rcl_get_default_allocator(); + rcl_allocator_t zero_allocator = static_cast( + rcutils_get_zero_initialized_allocator()); + rcl_node_t zero_node = rcl_get_zero_initialized_node(); + const char * unknown_node_name = "/test_rcl_get_client_names_and_types_by_node"; + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + // invalid node + ret = rcl_get_client_names_and_types_by_node( + nullptr, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_client_names_and_types_by_node( + &zero_node, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_client_names_and_types_by_node( + this->old_node_ptr, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid allocator + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, nullptr, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &zero_allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid names + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, nullptr, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, this->test_graph_node_name, nullptr, &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // test valid strings with invalid node names + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, "", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, "_InvalidNodeName", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid names and types + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, this->test_graph_node_name, "", nullptr); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // unknown node name + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, unknown_node_name, "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // valid call + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_reset_error(); +} + /* Test the rcl_count_publishers function. * * This does not test content of the response. @@ -728,6 +800,7 @@ struct expected_node_state size_t publishers; size_t subscribers; size_t services; + size_t clients; }; /** @@ -740,7 +813,7 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME std::string topic_name = "/test_node_info_functions__"; rcl_node_t * remote_node_ptr; rcl_allocator_t allocator = rcl_get_default_allocator(); - GetTopicsFunc sub_func, pub_func, service_func; + GetTopicsFunc sub_func, pub_func, service_func, client_func; rcl_context_t * remote_context_ptr; void SetUp() override @@ -787,6 +860,12 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME std::placeholders::_2, "/", std::placeholders::_3); + client_func = std::bind(rcl_get_client_names_and_types_by_node, + std::placeholders::_1, + &this->allocator, + std::placeholders::_2, + "/", + std::placeholders::_3); WaitForAllNodesAlive(); } @@ -858,6 +937,9 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Checking services from node"); expect_topics_types(node, service_func, node_state.services, test_graph_node_name, is_expect, is_success); + RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Checking clients from node"); + expect_topics_types(node, client_func, node_state.clients, + test_graph_node_name, is_expect, is_success); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Checking publishers from node"); expect_topics_types(node, pub_func, node_state.publishers, test_graph_node_name, is_expect, is_success); @@ -871,6 +953,9 @@ class NodeGraphMultiNodeFixture : public CLASSNAME(TestGraphFixture, RMW_IMPLEME RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Checking services from remote node"); expect_topics_types(node, service_func, remote_node_state.services, this->remote_node_name, is_expect, is_success); + RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Checking clients from remote node"); + expect_topics_types(node, client_func, remote_node_state.clients, + this->remote_node_name, is_expect, is_success); if (!is_success) { ret = rcl_wait_set_clear(wait_set_ptr); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -917,19 +1002,19 @@ TEST_F(NodeGraphMultiNodeFixture, test_node_info_subscriptions) EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); - VerifySubsystemCount(expected_node_state{1, 1, 0}, expected_node_state{1, 1, 0}); + VerifySubsystemCount(expected_node_state{1, 1, 0, 0}, expected_node_state{1, 1, 0, 0}); // Destroy the node's subscriber ret = rcl_subscription_fini(&sub, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); - VerifySubsystemCount(expected_node_state{1, 0, 0}, expected_node_state{1, 1, 0}); + VerifySubsystemCount(expected_node_state{1, 0, 0, 0}, expected_node_state{1, 1, 0, 0}); // Destroy the remote node's subdscriber ret = rcl_subscription_fini(&sub2, this->remote_node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); - VerifySubsystemCount(expected_node_state{1, 0, 0}, expected_node_state{1, 0, 0}); + VerifySubsystemCount(expected_node_state{1, 0, 0, 0}, expected_node_state{1, 0, 0, 0}); } TEST_F(NodeGraphMultiNodeFixture, test_node_info_publishers) @@ -942,14 +1027,14 @@ TEST_F(NodeGraphMultiNodeFixture, test_node_info_publishers) ret = rcl_publisher_init(&pub, this->node_ptr, ts, this->topic_name.c_str(), &pub_ops); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); - VerifySubsystemCount(expected_node_state{2, 0, 0}, expected_node_state{1, 0, 0}); + VerifySubsystemCount(expected_node_state{2, 0, 0, 0}, expected_node_state{1, 0, 0, 0}); RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Destroyed publisher"); // Destroy the publisher. ret = rcl_publisher_fini(&pub, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; rcl_reset_error(); - VerifySubsystemCount(expected_node_state{1, 0, 0}, expected_node_state{1, 0, 0}); + VerifySubsystemCount(expected_node_state{1, 0, 0, 0}, expected_node_state{1, 0, 0, 0}); } TEST_F(NodeGraphMultiNodeFixture, test_node_info_services) @@ -961,12 +1046,29 @@ TEST_F(NodeGraphMultiNodeFixture, test_node_info_services) auto ts1 = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); ret = rcl_service_init(&service, this->node_ptr, ts1, service_name, &service_options); ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - VerifySubsystemCount(expected_node_state{1, 0, 1}, expected_node_state{1, 0, 0}); + VerifySubsystemCount(expected_node_state{1, 0, 1, 0}, expected_node_state{1, 0, 0, 0}); // Destroy service. ret = rcl_service_fini(&service, this->node_ptr); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - VerifySubsystemCount(expected_node_state{1, 0, 0}, expected_node_state{1, 0, 0}); + VerifySubsystemCount(expected_node_state{1, 0, 0, 0}, expected_node_state{1, 0, 0, 0}); +} + +TEST_F(NodeGraphMultiNodeFixture, test_node_info_clients) +{ + rcl_ret_t ret; + const char * service_name = "test_service"; + rcl_client_t client = rcl_get_zero_initialized_client(); + rcl_client_options_t client_options = rcl_client_get_default_options(); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); + ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + VerifySubsystemCount(expected_node_state{1, 0, 0, 1}, expected_node_state{1, 0, 0, 0}); + + // Destroy client + ret = rcl_client_fini(&client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + VerifySubsystemCount(expected_node_state{1, 0, 0, 0}, expected_node_state{1, 0, 0, 0}); } /*