From dfbf07bc3e67bf84d8f9b6756dd3ca4cd7746095 Mon Sep 17 00:00:00 2001
From: Michael Carroll <michael@openrobotics.org>
Date: Mon, 18 Mar 2019 13:47:48 -0500
Subject: [PATCH 1/3] Fix regression around fully qualified node name.

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

Signed-off-by: Michael Carroll <michael@openrobotics.org>
---
 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 4973a9b5b..5aa5ec9ae 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 d17d74832..2483dc4aa 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 54d689d77..b97b2e595 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);
+  }
+}

From ba1e93df28a8e20a4c077775c5d8cae41b4b2c27 Mon Sep 17 00:00:00 2001
From: Michael Carroll <michael@openrobotics.org>
Date: Mon, 18 Mar 2019 14:20:54 -0500
Subject: [PATCH 2/3] Clean up test code based on feedback.

Signed-off-by: Michael Carroll <michael@openrobotics.org>
---
 rcl/test/rcl/test_node.cpp | 112 +++++++++----------------------------
 1 file changed, 26 insertions(+), 86 deletions(-)

diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp
index b97b2e595..b1527ce8c 100644
--- a/rcl/test/rcl/test_node.cpp
+++ b/rcl/test/rcl/test_node.cpp
@@ -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);
@@ -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);
@@ -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);
@@ -236,7 +221,7 @@ 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));
   }
@@ -244,7 +229,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_accessors)
   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));
   }
@@ -644,7 +629,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name
     ret = rcl_node_init(&node, name, "/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);
+    EXPECT_NE(actual_node_logger_name, nullptr);
     if (actual_node_logger_name) {
       EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
     }
@@ -658,7 +643,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name
     ret = rcl_node_init(&node, name, "", &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);
+    EXPECT_NE(actual_node_logger_name, nullptr);
     if (actual_node_logger_name) {
       EXPECT_EQ(std::string(name), std::string(actual_node_logger_name));
     }
@@ -686,7 +671,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name
     ret = rcl_node_init(&node, name, "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);
+    EXPECT_NE(actual_node_logger_name, nullptr);
     if (actual_node_logger_name) {
       EXPECT_EQ("ns." + std::string(name), std::string(actual_node_logger_name));
     }
@@ -700,7 +685,7 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_logger_name
     ret = rcl_node_init(&node, name, "/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);
+    EXPECT_NE(actual_node_logger_name, nullptr);
     if (actual_node_logger_name) {
       EXPECT_EQ("ns.sub_1.sub_2." + std::string(name), std::string(actual_node_logger_name));
     }
@@ -744,18 +729,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
     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));
-    }
+    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);
@@ -771,18 +747,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
     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));
-    }
+    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);
@@ -798,18 +765,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
     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));
-    }
+    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);
@@ -824,18 +782,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
     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));
-    }
+    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);
@@ -851,18 +800,9 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
     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));
-    }
+    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);

From 7a9e5e2a08e0c7efde2d4b304271a295e9e227b3 Mon Sep 17 00:00:00 2001
From: Michael Carroll <michael@openrobotics.org>
Date: Mon, 18 Mar 2019 15:57:56 -0500
Subject: [PATCH 3/3] Combine tests to prevent Connext timeout.

Signed-off-by: Michael Carroll <michael@openrobotics.org>
---
 rcl/test/rcl/test_node.cpp | 122 ++++++-------------------------------
 1 file changed, 20 insertions(+), 102 deletions(-)

diff --git a/rcl/test/rcl/test_node.cpp b/rcl/test/rcl/test_node.cpp
index b1527ce8c..0e6e9b46e 100644
--- a/rcl/test/rcl/test_node.cpp
+++ b/rcl/test/rcl/test_node.cpp
@@ -599,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().
@@ -619,116 +619,25 @@ 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;
-  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_logger_name = rcl_node_get_logger_name(&node);
-    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_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_logger_name = rcl_node_get_logger_name(&node);
-    EXPECT_NE(actual_node_logger_name, nullptr);
-    if (actual_node_logger_name) {
-      EXPECT_EQ(std::string(name), std::string(actual_node_logger_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_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));
-    }
-    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);
-    ASSERT_EQ(RCL_RET_OK, ret);
-    actual_node_logger_name = rcl_node_get_logger_name(&node);
-    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_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_logger_name = rcl_node_get_logger_name(&node);
-    EXPECT_NE(actual_node_logger_name, nullptr);
-    if (actual_node_logger_name) {
-      EXPECT_EQ("ns.sub_1.sub_2." + std::string(name), std::string(actual_node_logger_name));
-    }
-    rcl_ret_t ret = rcl_node_fini(&node);
-    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);
+    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);
     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);
@@ -740,13 +649,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
   // 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);
     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);
@@ -758,13 +669,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
   // 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);
     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);
@@ -776,12 +689,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
   // 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);
     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);
@@ -793,13 +709,15 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names_and_n
   // 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);
     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);