diff --git a/rcl/src/rcl/graph.c b/rcl/src/rcl/graph.c index 574a7d0f2..f16efe4db 100644 --- a/rcl/src/rcl/graph.c +++ b/rcl/src/rcl/graph.c @@ -42,7 +42,7 @@ rcl_get_publisher_names_and_types_by_node( if (!rcl_node_is_valid(node)) { return RCL_RET_NODE_INVALID; } - RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT); + 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(topic_names_and_types, RCL_RET_INVALID_ARGUMENT); @@ -80,7 +80,7 @@ rcl_get_subscriber_names_and_types_by_node( if (!rcl_node_is_valid(node)) { return RCL_RET_NODE_INVALID; } - RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT); + 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(topic_names_and_types, RCL_RET_INVALID_ARGUMENT); @@ -117,7 +117,7 @@ rcl_get_service_names_and_types_by_node( if (!rcl_node_is_valid(node)) { return RCL_RET_NODE_INVALID; } - RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT); + 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); @@ -152,7 +152,7 @@ rcl_get_topic_names_and_types( if (!rcl_node_is_valid(node)) { return RCL_RET_NODE_INVALID; // error already set } - RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(topic_names_and_types, RCL_RET_INVALID_ARGUMENT); rmw_ret_t rmw_ret; rmw_ret = rmw_names_and_types_check_zero(topic_names_and_types); @@ -178,6 +178,7 @@ rcl_get_service_names_and_types( if (!rcl_node_is_valid(node)) { return RCL_RET_NODE_INVALID; // error already set } + RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT); RCL_CHECK_ARGUMENT_FOR_NULL(service_names_and_types, RCL_RET_INVALID_ARGUMENT); rmw_ret_t rmw_ret; rmw_ret = rmw_names_and_types_check_zero(service_names_and_types); @@ -200,6 +201,7 @@ rcl_names_and_types_init( rcl_allocator_t * allocator) { RCL_CHECK_ARGUMENT_FOR_NULL(names_and_types, RCL_RET_INVALID_ARGUMENT); + RCL_CHECK_ALLOCATOR(allocator, return RCL_RET_INVALID_ARGUMENT); rmw_ret_t rmw_ret = rmw_names_and_types_init(names_and_types, size, allocator); return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret); } diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 56fab0921..9cf17c1c7 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -100,7 +100,7 @@ function(test_target_function) # TODO(mm318): why rmw_connext tests run much slower than rmw_fastrtps and rmw_opensplice tests elseif(rmw_implementation STREQUAL "rmw_connext_cpp") message(STATUS "Increasing test_graph${target_suffix} test timeout.") - set(AMENT_GTEST_ARGS TIMEOUT 90) + set(AMENT_GTEST_ARGS TIMEOUT 180) endif() rcl_add_custom_gtest(test_graph${target_suffix} SRCS rcl/test_graph.cpp diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 4e424ae1b..d611bafbd 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -131,7 +131,7 @@ class CLASSNAME (TestGraphFixture, RMW_IMPLEMENTATION) : public ::testing::Test /* Test the rcl_get_topic_names_and_types and rcl_destroy_topic_names_and_types functions. * - * This does not test content of the rcl_topic_names_and_types_t structure. + * This does not test content of the rcl_names_and_types_t structure. */ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), @@ -139,6 +139,8 @@ TEST_F( ) { 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_names_and_types_t tnat {}; rcl_node_t zero_node = rcl_get_zero_initialized_node(); // invalid node @@ -155,6 +157,9 @@ TEST_F( ret = rcl_get_topic_names_and_types(this->node_ptr, nullptr, false, &tnat); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; rcl_reset_error(); + ret = rcl_get_topic_names_and_types(this->node_ptr, &zero_allocator, false, &tnat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); // invalid topic_names_and_types ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; @@ -170,6 +175,52 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } +/* Test the rcl_get_service_names_and_types function. + * + * This does not test content of the rcl_names_and_types_t structure. + */ +TEST_F( + CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), + test_rcl_get_service_names_and_types +) { + 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_names_and_types_t tnat {}; + rcl_node_t zero_node = rcl_get_zero_initialized_node(); + // invalid node + ret = rcl_get_service_names_and_types(nullptr, &allocator, &tnat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_service_names_and_types(&zero_node, &allocator, &tnat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_service_names_and_types(this->old_node_ptr, &allocator, &tnat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid allocator + ret = rcl_get_service_names_and_types(this->node_ptr, nullptr, &tnat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_service_names_and_types(this->node_ptr, &zero_allocator, &tnat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid service_names_and_types + ret = rcl_get_service_names_and_types(this->node_ptr, &allocator, nullptr); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // invalid argument to rcl_destroy_service_names_and_types + ret = rcl_names_and_types_fini(nullptr); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // valid calls + ret = rcl_get_service_names_and_types(this->node_ptr, &allocator, &tnat); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ret = rcl_names_and_types_fini(&tnat); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; +} + /* Test the rcl_names_and_types_init function. */ TEST_F( @@ -178,6 +229,8 @@ TEST_F( ) { 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_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); // invalid names and types ret = rcl_names_and_types_init(nullptr, 10, &allocator); @@ -187,6 +240,9 @@ TEST_F( ret = rcl_names_and_types_init(&nat, 10, nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; rcl_reset_error(); + ret = rcl_names_and_types_init(&nat, 10, &zero_allocator); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); // zero size ret = rcl_names_and_types_init(&nat, 0, &allocator); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -205,9 +261,261 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; } +/* Test the rcl_get_publisher_names_and_types_by_node function. + * + * This does not test content of the response. + */ +TEST_F( + CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), + test_rcl_get_publisher_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_publisher_names_and_types_by_node"; + // const char * unknown_node_ns = "/test/namespace"; + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + // invalid node + ret = rcl_get_publisher_names_and_types_by_node( + nullptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_publisher_names_and_types_by_node( + &zero_node, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_publisher_names_and_types_by_node( + this->old_node_ptr, &allocator, false, 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_publisher_names_and_types_by_node( + this->node_ptr, nullptr, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &zero_allocator, false, 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_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, nullptr, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, 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_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, "", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, "_InvalidNodeName", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_publisher_names_and_types_by_node( + // this->node_ptr, &allocator, false, this->test_graph_node_name, "_!invalidNs", &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // invalid names and types + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, 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_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, unknown_node_name, "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // unknown node namespace + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_publisher_names_and_types_by_node( + // this->node_ptr, &allocator, false, this->test_graph_node_name, unknown_node_ns, &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // valid call + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_reset_error(); +} + +/* Test the rcl_get_subscriber_names_and_types_by_node function. + * + * This does not test content of the response. + */ +TEST_F( + CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), + test_rcl_get_subscriber_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_subscriber_names_and_types_by_node"; + // const char * unknown_node_ns = "/test/namespace"; + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + // invalid node + ret = rcl_get_subscriber_names_and_types_by_node( + nullptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_subscriber_names_and_types_by_node( + &zero_node, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_subscriber_names_and_types_by_node( + this->old_node_ptr, &allocator, false, 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_subscriber_names_and_types_by_node( + this->node_ptr, nullptr, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &zero_allocator, false, 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_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, nullptr, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, 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_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, "", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, "_InvalidNodeName", "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_subscriber_names_and_types_by_node( + // this->node_ptr, &allocator, false, this->test_graph_node_name, "_!invalidNs", &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // invalid names and types + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, 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_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, unknown_node_name, "", &nat); + EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + rcl_reset_error(); + // unknown node namespace + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_subscriber_names_and_types_by_node( + // this->node_ptr, &allocator, false, this->test_graph_node_name, unknown_node_ns, &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // valid call + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + rcl_reset_error(); +} + +/* Test the rcl_get_service_names_and_types_by_node function. + * + * This does not test content of the response. + */ +TEST_F( + CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), + test_rcl_get_service_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_service_names_and_types_by_node"; + // const char * unknown_node_ns = "/test/namespace"; + rcl_names_and_types_t nat = rcl_get_zero_initialized_names_and_types(); + // invalid node + ret = rcl_get_service_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_service_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_service_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_service_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_service_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_service_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_service_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_service_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_service_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(); + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_service_names_and_types_by_node( + // this->node_ptr, &allocator, false, this->test_graph_node_name, "_!invalidNs", &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // invalid names and types + ret = rcl_get_service_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_service_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(); + // unknown node namespace + // TODO(jacobperron): This succeeds, but should fail due to invalid namespace + // ret = rcl_get_service_names_and_types_by_node( + // this->node_ptr, &allocator, this->test_graph_node_name, unknown_node_ns, &nat); + // EXPECT_EQ(RCL_RET_ERROR, ret) << rcl_get_error_string().str; + // rcl_reset_error(); + // valid call + ret = rcl_get_service_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 the response. + * This does not test content of the response. */ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), @@ -244,7 +552,7 @@ TEST_F( /* Test the rcl_count_subscribers function. * - * This does not test content the response. + * This does not test content of the response. */ TEST_F( CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION),