Skip to content

Commit

Permalink
Fix regression around fully qualified node name. (#402)
Browse files Browse the repository at this point in the history
* Fix regression around fully qualified node name.

Regression was introduced in 114bc52 (PR #381).

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Clean up test code based on feedback.

Signed-off-by: Michael Carroll <michael@openrobotics.org>

* Combine tests to prevent Connext timeout.

Signed-off-by: Michael Carroll <michael@openrobotics.org>
  • Loading branch information
mjcarroll authored Mar 18, 2019
1 parent dcffef5 commit 29b0838
Show file tree
Hide file tree
Showing 3 changed files with 82 additions and 60 deletions.
8 changes: 6 additions & 2 deletions rcl/src/rcl/node.c
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
16 changes: 8 additions & 8 deletions rcl/test/rcl/test_get_node_names.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
118 changes: 68 additions & 50 deletions rcl/test/rcl/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -173,10 +173,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
EXPECT_EQ(nullptr, actual_node_name);
rcl_reset_error();
actual_node_name = rcl_node_get_name(&invalid_node);
EXPECT_TRUE(actual_node_name ? true : false);
if (actual_node_name) {
EXPECT_STREQ(name, actual_node_name);
}
EXPECT_STREQ(name, actual_node_name);
rcl_reset_error();
EXPECT_NO_MEMORY_OPERATIONS({
actual_node_name = rcl_node_get_name(&node);
Expand All @@ -194,18 +191,12 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
EXPECT_EQ(nullptr, actual_node_namespace);
rcl_reset_error();
actual_node_namespace = rcl_node_get_namespace(&invalid_node);
EXPECT_TRUE(actual_node_namespace ? true : false);
if (actual_node_namespace) {
EXPECT_STREQ(namespace_, actual_node_namespace);
}
EXPECT_STREQ(namespace_, actual_node_namespace);
rcl_reset_error();
EXPECT_NO_MEMORY_OPERATIONS({
actual_node_namespace = rcl_node_get_namespace(&node);
});
EXPECT_TRUE(actual_node_namespace ? true : false);
if (actual_node_namespace) {
EXPECT_EQ(std::string(namespace_), std::string(actual_node_namespace));
}
EXPECT_STREQ(namespace_, actual_node_namespace);
// Test rcl_node_get_fully_qualified_name().
const char * actual_fq_node_name;
actual_fq_node_name = rcl_node_get_fully_qualified_name(nullptr);
Expand All @@ -215,18 +206,12 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
EXPECT_EQ(nullptr, actual_fq_node_name);
rcl_reset_error();
actual_fq_node_name = rcl_node_get_fully_qualified_name(&invalid_node);
EXPECT_TRUE(actual_fq_node_name ? true : false);
if (actual_fq_node_name) {
EXPECT_STREQ(fq_name, actual_fq_node_name);
}
EXPECT_STREQ(fq_name, actual_fq_node_name);
rcl_reset_error();
EXPECT_NO_MEMORY_OPERATIONS({
actual_fq_node_name = rcl_node_get_fully_qualified_name(&node);
});
EXPECT_TRUE(actual_fq_node_name ? true : false);
if (actual_fq_node_name) {
EXPECT_EQ(std::string(fq_name), std::string(actual_fq_node_name));
}
EXPECT_STREQ(fq_name, actual_fq_node_name);
// Test rcl_node_get_logger_name().
const char * actual_node_logger_name;
actual_node_logger_name = rcl_node_get_logger_name(nullptr);
Expand All @@ -236,15 +221,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
EXPECT_EQ(nullptr, actual_node_logger_name);
rcl_reset_error();
actual_node_logger_name = rcl_node_get_logger_name(&invalid_node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
EXPECT_NE(actual_node_logger_name, nullptr);
if (actual_node_logger_name) {
EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
}
rcl_reset_error();
EXPECT_NO_MEMORY_OPERATIONS({
actual_node_logger_name = rcl_node_get_logger_name(&node);
});
EXPECT_TRUE(actual_node_logger_name ? true : false);
EXPECT_NE(actual_node_logger_name, nullptr);
if (actual_node_logger_name) {
EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
}
Expand Down Expand Up @@ -614,9 +599,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_namespace_r
}
}

/* Tests the logger name associated with the node.
/* Tests the logger name as well as fully qualified name associated with the node.
*/
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name) {
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) {
rcl_ret_t ret;

// Initialize rcl with rcl_init().
Expand All @@ -634,76 +619,109 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name
ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context));
});

const char * name = "node";
const char * actual_node_logger_name;
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);
ret = rcl_node_init(&node, "node", "/ns", &context, &default_options);
ASSERT_EQ(RCL_RET_OK, ret);

actual_node_logger_name = rcl_node_get_logger_name(&node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
if (actual_node_logger_name) {
EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
}
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_STREQ("ns.node", actual_node_logger_name);
EXPECT_STREQ("node", actual_node_name);
EXPECT_STREQ("/ns", actual_node_namespace);
EXPECT_STREQ("/ns/node", 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);
ret = rcl_node_init(&node, "node", "", &context, &default_options);
ASSERT_EQ(RCL_RET_OK, ret);

actual_node_logger_name = rcl_node_get_logger_name(&node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
if (actual_node_logger_name) {
EXPECT_EQ(std::string(name), std::string(actual_node_logger_name));
}
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_STREQ("node", actual_node_logger_name);
EXPECT_STREQ("node", actual_node_name);
EXPECT_STREQ("/", actual_node_namespace);
EXPECT_STREQ("/node", 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);
ret = rcl_node_init(&node, "node", "/", &context, &default_options);
ASSERT_EQ(RCL_RET_OK, ret);

actual_node_logger_name = rcl_node_get_logger_name(&node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
if (actual_node_logger_name) {
EXPECT_EQ(std::string(name), std::string(actual_node_logger_name));
}
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_STREQ("node", actual_node_logger_name);
EXPECT_STREQ("node", actual_node_name);
EXPECT_STREQ("/", actual_node_namespace);
EXPECT_STREQ("/node", 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);
ret = rcl_node_init(&node, "node", "ns", &context, &default_options);
ASSERT_EQ(RCL_RET_OK, ret);

actual_node_logger_name = rcl_node_get_logger_name(&node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
if (actual_node_logger_name) {
EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
}
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_STREQ("ns.node", actual_node_logger_name);
EXPECT_STREQ("node", actual_node_name);
EXPECT_STREQ("/ns", actual_node_namespace);
EXPECT_STREQ("/ns/node", 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);
ret = rcl_node_init(&node, "node", "/ns/sub_1/sub_2", &context, &default_options);
ASSERT_EQ(RCL_RET_OK, ret);

actual_node_logger_name = rcl_node_get_logger_name(&node);
EXPECT_TRUE(actual_node_logger_name ? true : false);
if (actual_node_logger_name) {
EXPECT_EQ("ns.sub_1.sub_2." + std::string(name), std::string(actual_node_logger_name));
}
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_STREQ("ns.sub_1.sub_2.node", actual_node_logger_name);
EXPECT_STREQ("node", actual_node_name);
EXPECT_STREQ("/ns/sub_1/sub_2", actual_node_namespace);
EXPECT_STREQ("/ns/sub_1/sub_2/node", actual_node_fq_name);

rcl_ret_t ret = rcl_node_fini(&node);
EXPECT_EQ(RCL_RET_OK, ret);
}
Expand Down

0 comments on commit 29b0838

Please sign in to comment.