From 17ca695c40897568b8cb270ea07fb6df9ea294b8 Mon Sep 17 00:00:00 2001 From: Michael Carroll Date: Mon, 18 Mar 2019 13:47:48 -0500 Subject: [PATCH] Fix regression around fully qualified node name. Regression was introduced in 114bc5289 (PR #381). --- rcl/src/rcl/node.c | 8 +- rcl/test/rcl/test_get_node_names.cpp | 16 +-- rcl/test/rcl/test_node.cpp | 160 +++++++++++++++++++++++++++ 3 files changed, 174 insertions(+), 10 deletions(-) diff --git a/rcl/src/rcl/node.c b/rcl/src/rcl/node.c index 4973a9b5b2..5aa5ec9ae9 100644 --- a/rcl/src/rcl/node.c +++ b/rcl/src/rcl/node.c @@ -241,8 +241,12 @@ rcl_node_init( local_namespace_ = remapped_namespace; } - // compute fully qualified name of the node - node->impl->fq_name = rcutils_format_string(*allocator, "%s/%s", local_namespace_, name); + // compute fully qualfied name of the node. + if ('/' == local_namespace_[strlen(local_namespace_) - 1]) { + node->impl->fq_name = rcutils_format_string(*allocator, "%s%s", local_namespace_, name); + } else { + node->impl->fq_name = rcutils_format_string(*allocator, "%s/%s", local_namespace_, name); + } // node logger name node->impl->logger_name = rcl_create_node_logger_name(name, local_namespace_, allocator); diff --git a/rcl/test/rcl/test_get_node_names.cpp b/rcl/test/rcl/test_get_node_names.cpp index d17d748327..2483dc4aa4 100644 --- a/rcl/test/rcl/test_get_node_names.cpp +++ b/rcl/test/rcl/test_get_node_names.cpp @@ -107,16 +107,16 @@ TEST_F(CLASSNAME(TestGetNodeNames, RMW_IMPLEMENTATION), test_rcl_get_node_names) ss << node_names.data[i] << std::endl; } EXPECT_EQ(size_t(4), node_names.size) << ss.str(); - EXPECT_EQ(0, strcmp(node1_name, node_names.data[0])); - EXPECT_EQ(0, strcmp(node2_name, node_names.data[1])); - EXPECT_EQ(0, strcmp(node3_name, node_names.data[2])); - EXPECT_EQ(0, strcmp(node4_name, node_names.data[3])); + EXPECT_STREQ(node1_name, node_names.data[0]); + EXPECT_STREQ(node2_name, node_names.data[1]); + EXPECT_STREQ(node3_name, node_names.data[2]); + EXPECT_STREQ(node4_name, node_names.data[3]); EXPECT_EQ(size_t(4), node_namespaces.size) << ss.str(); - EXPECT_EQ(0, strcmp(node1_namespace, node_namespaces.data[0])); - EXPECT_EQ(0, strcmp(node2_namespace, node_namespaces.data[1])); - EXPECT_EQ(0, strcmp(node3_namespace, node_namespaces.data[2])); - EXPECT_EQ(0, strcmp(node4_namespace, node_namespaces.data[3])); + EXPECT_STREQ(node1_namespace, node_namespaces.data[0]); + EXPECT_STREQ(node2_namespace, node_namespaces.data[1]); + EXPECT_STREQ(node3_namespace, node_namespaces.data[2]); + EXPECT_STREQ(node4_namespace, node_namespaces.data[3]); ret = rcutils_string_array_fini(&node_names); ASSERT_EQ(RCUTILS_RET_OK, ret); diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp index 54d689d77a..b97b2e5950 100644 --- a/rcl/test/rcl/test_node.cpp +++ b/rcl/test/rcl/test_node.cpp @@ -708,3 +708,163 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name EXPECT_EQ(RCL_RET_OK, ret); } } + +/* Tests the names and namespaces associated with the node. + */ +TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_namespaces) { + rcl_ret_t ret; + + // Initialize rcl with rcl_init(). + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)) << rcl_get_error_string().str; + }); + rcl_context_t context = rcl_get_zero_initialized_context(); + ret = rcl_init(0, nullptr, &init_options, &context); + ASSERT_EQ(RCL_RET_OK, ret); + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT({ + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); + }); + + const char * name = "node"; + const char * actual_node_name; + const char * actual_node_namespace; + const char * actual_node_fq_name; + rcl_node_options_t default_options = rcl_node_get_default_options(); + + // First do a normal node namespace. + { + rcl_node_t node = rcl_get_zero_initialized_node(); + ret = rcl_node_init(&node, name, "/ns", &context, &default_options); + ASSERT_EQ(RCL_RET_OK, ret); + actual_node_name = rcl_node_get_name(&node); + actual_node_namespace = rcl_node_get_namespace(&node); + actual_node_fq_name = rcl_node_get_fully_qualified_name(&node); + + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_EQ("node", std::string(actual_node_name)); + } + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_EQ("/ns", std::string(actual_node_namespace)); + } + EXPECT_TRUE(actual_node_fq_name ? true : false); + if (actual_node_fq_name) { + EXPECT_EQ("/ns/node", std::string(actual_node_fq_name)); + } + + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + } + + // Node namespace that is an empty string. + { + rcl_node_t node = rcl_get_zero_initialized_node(); + ret = rcl_node_init(&node, name, "", &context, &default_options); + ASSERT_EQ(RCL_RET_OK, ret); + + actual_node_name = rcl_node_get_name(&node); + actual_node_namespace = rcl_node_get_namespace(&node); + actual_node_fq_name = rcl_node_get_fully_qualified_name(&node); + + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_EQ("node", std::string(actual_node_name)); + } + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_EQ("/", std::string(actual_node_namespace)); + } + EXPECT_TRUE(actual_node_fq_name ? true : false); + if (actual_node_fq_name) { + EXPECT_EQ("/node", std::string(actual_node_fq_name)); + } + + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + } + + // Node namespace that is just a forward slash. + { + rcl_node_t node = rcl_get_zero_initialized_node(); + ret = rcl_node_init(&node, name, "/", &context, &default_options); + ASSERT_EQ(RCL_RET_OK, ret); + + actual_node_name = rcl_node_get_name(&node); + actual_node_namespace = rcl_node_get_namespace(&node); + actual_node_fq_name = rcl_node_get_fully_qualified_name(&node); + + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_EQ("node", std::string(actual_node_name)); + } + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_EQ("/", std::string(actual_node_namespace)); + } + EXPECT_TRUE(actual_node_fq_name ? true : false); + if (actual_node_fq_name) { + EXPECT_EQ("/node", std::string(actual_node_fq_name)); + } + + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + } + + // Node namespace that is not absolute. + { + rcl_node_t node = rcl_get_zero_initialized_node(); + ret = rcl_node_init(&node, name, "ns", &context, &default_options); + + actual_node_name = rcl_node_get_name(&node); + actual_node_namespace = rcl_node_get_namespace(&node); + actual_node_fq_name = rcl_node_get_fully_qualified_name(&node); + + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_EQ("node", std::string(actual_node_name)); + } + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_EQ("/ns", std::string(actual_node_namespace)); + } + EXPECT_TRUE(actual_node_fq_name ? true : false); + if (actual_node_fq_name) { + EXPECT_EQ("/ns/node", std::string(actual_node_fq_name)); + } + + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + } + + // Nested namespace. + { + rcl_node_t node = rcl_get_zero_initialized_node(); + ret = rcl_node_init(&node, name, "/ns/sub_1/sub_2", &context, &default_options); + ASSERT_EQ(RCL_RET_OK, ret); + + actual_node_name = rcl_node_get_name(&node); + actual_node_namespace = rcl_node_get_namespace(&node); + actual_node_fq_name = rcl_node_get_fully_qualified_name(&node); + + EXPECT_TRUE(actual_node_name ? true : false); + if (actual_node_name) { + EXPECT_EQ("node", std::string(actual_node_name)); + } + EXPECT_TRUE(actual_node_namespace ? true : false); + if (actual_node_namespace) { + EXPECT_EQ("/ns/sub_1/sub_2", std::string(actual_node_namespace)); + } + EXPECT_TRUE(actual_node_fq_name ? true : false); + if (actual_node_fq_name) { + EXPECT_EQ("/ns/sub_1/sub_2/node", std::string(actual_node_fq_name)); + } + + rcl_ret_t ret = rcl_node_fini(&node); + EXPECT_EQ(RCL_RET_OK, ret); + } +}