From d282d6221cc4e2aaf40efb93799f1668ada39b1f Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 24 Jun 2020 19:00:16 -0300 Subject: [PATCH 01/22] Add tests not empty names_and_types Signed-off-by: Jorge Perez --- rcl/test/rcl/test_graph.cpp | 38 +++++++++++++++++++++++++++++++++++-- 1 file changed, 36 insertions(+), 2 deletions(-) diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index d72a08997..1acaf4ece 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -149,7 +149,7 @@ TEST_F( 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_names_and_types_t tnat = rcl_get_zero_initialized_names_and_types(); rcl_node_t zero_node = rcl_get_zero_initialized_node(); // invalid node ret = rcl_get_topic_names_and_types(nullptr, &allocator, false, &tnat); @@ -172,6 +172,11 @@ TEST_F( 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; rcl_reset_error(); + tnat.names.size = 1; + ret = rcl_get_topic_names_and_types(this->node_ptr, &allocator, false, &tnat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + tnat.names.size = 0; // invalid argument to rcl_destroy_topic_names_and_types ret = rcl_names_and_types_fini(nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; @@ -195,7 +200,7 @@ TEST_F( 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_names_and_types_t tnat = rcl_get_zero_initialized_names_and_types(); rcl_node_t zero_node = rcl_get_zero_initialized_node(); // invalid node ret = rcl_get_service_names_and_types(nullptr, &allocator, &tnat); @@ -218,6 +223,11 @@ TEST_F( 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(); + tnat.names.size = 1; + ret = rcl_get_service_names_and_types(this->node_ptr, &allocator, &tnat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + tnat.names.size = 0; // 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; @@ -334,6 +344,12 @@ TEST_F( 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(); + nat.names.size = 1; + ret = rcl_get_publisher_names_and_types_by_node( + this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + nat.names.size = 0; // unknown node name ret = rcl_get_publisher_names_and_types_by_node( this->node_ptr, &allocator, false, unknown_node_name, "", &nat); @@ -419,6 +435,12 @@ TEST_F( 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(); + nat.names.size = 1; + ret = rcl_get_subscriber_names_and_types_by_node( + this->node_ptr, &allocator, false, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + nat.names.size = 0; // unknown node name ret = rcl_get_subscriber_names_and_types_by_node( this->node_ptr, &allocator, false, unknown_node_name, "", &nat); @@ -501,6 +523,12 @@ TEST_F( 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(); + nat.names.size = 1; + ret = rcl_get_service_names_and_types_by_node( + this->node_ptr, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + nat.names.size = 0; // unknown node name ret = rcl_get_service_names_and_types_by_node( this->node_ptr, &allocator, unknown_node_name, "", &nat); @@ -584,6 +612,12 @@ TEST_F( 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(); + nat.names.size = 1; + ret = rcl_get_client_names_and_types_by_node( + this->node_ptr, &allocator, this->test_graph_node_name, "", &nat); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + nat.names.size = 0; // unknown node name ret = rcl_get_client_names_and_types_by_node( this->node_ptr, &allocator, unknown_node_name, "", &nat); From 70b1671ec3bd09efc49d7679de6f4595a99d62ed Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 25 Jun 2020 10:30:12 -0300 Subject: [PATCH 02/22] Add tests graph.c module Signed-off-by: Jorge Perez --- rcl/test/rcl/test_graph.cpp | 157 ++++++++++++++++++++++++++++++++++++ 1 file changed, 157 insertions(+) diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 1acaf4ece..7ef863094 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -1388,3 +1388,160 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_rcl_service_server_ wait_for_service_state_to_change(false, is_available); ASSERT_FALSE(is_available); } + +/* Test passing invalid params to server_is_available + */ +TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_server_available) { + // Create a client which will be used to call the function. + rcl_client_t client = rcl_get_zero_initialized_client(); + auto ts = ROSIDL_GET_SRV_TYPE_SUPPORT(test_msgs, srv, BasicTypes); + const char * service_name = "/service_test_rcl_service_server_is_available"; + rcl_client_options_t client_options = rcl_client_get_default_options(); + rcl_ret_t ret = rcl_client_init(&client, this->node_ptr, ts, service_name, &client_options); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + rcl_ret_t ret = rcl_client_fini(&client, this->node_ptr); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + }); + // Check, knowing there is no service server (created by us at least). + bool is_available; + ret = rcl_service_server_is_available(this->node_ptr, &client, &is_available); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ASSERT_FALSE(is_available); + + ret = rcl_service_server_is_available(nullptr, &client, &is_available); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); + rcl_node_t not_init_node = rcl_get_zero_initialized_node(); + ret = rcl_service_server_is_available(¬_init_node, &client, &is_available); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); +} + +/* Test passing invalid params to get_node_names functions + */ +TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) { + rcutils_string_array_t node_names = rcutils_get_zero_initialized_string_array(); + rcutils_string_array_t node_namespaces = rcutils_get_zero_initialized_string_array(); + + rcutils_string_array_t node_names_2 = rcutils_get_zero_initialized_string_array(); + rcutils_string_array_t node_namespaces_2 = rcutils_get_zero_initialized_string_array(); + rcutils_string_array_t node_enclaves = rcutils_get_zero_initialized_string_array(); + rcl_ret_t ret = RCL_RET_OK; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + ret = rcutils_string_array_fini(&node_names); + ASSERT_EQ(RCUTILS_RET_OK, ret); + ret = rcutils_string_array_fini(&node_namespaces); + ASSERT_EQ(RCUTILS_RET_OK, ret); + ret = rcutils_string_array_fini(&node_enclaves); + ASSERT_EQ(RCUTILS_RET_OK, ret); + }); + rcl_allocator_t allocator = rcl_get_default_allocator(); + + ret = rcl_get_node_names(nullptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); + ret = rcl_get_node_names_with_enclaves( + nullptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); + + rcl_node_t not_init_node = rcl_get_zero_initialized_node(); + ret = rcl_get_node_names(¬_init_node, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); + ret = rcl_get_node_names_with_enclaves( + ¬_init_node, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_NODE_INVALID, ret); + rcl_reset_error(); + + ret = rcl_get_node_names(this->node_ptr, allocator, nullptr, &node_namespaces); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, nullptr, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, nullptr); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, nullptr, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, nullptr); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + + node_names.size = 1; + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_names.size = 0; + + ret = rcutils_string_array_init(&node_names, 1, &allocator); + EXPECT_EQ(RCL_RET_OK, ret); + node_names.size = 0; + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_names.size = 1; + ret = rcutils_string_array_fini(&node_names); + EXPECT_EQ(RCL_RET_OK, ret); + + node_namespaces.size = 1; + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_namespaces.size = 0; + + ret = rcutils_string_array_init(&node_namespaces, 1, &allocator); + EXPECT_EQ(RCL_RET_OK, ret); + node_namespaces.size = 0; + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_namespaces.size = 1; + ret = rcutils_string_array_fini(&node_namespaces); + EXPECT_EQ(RCL_RET_OK, ret); + + node_enclaves.size = 1; + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_enclaves.size = 0; + + ret = rcutils_string_array_init(&node_enclaves, 1, &allocator); + EXPECT_EQ(RCL_RET_OK, ret); + node_enclaves.size = 0; + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + node_enclaves.size = 1; + ret = rcutils_string_array_fini(&node_enclaves); + EXPECT_EQ(RCL_RET_OK, ret); + + // Expected usage + ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); + EXPECT_EQ(RCL_RET_OK, ret); + ret = rcl_get_node_names_with_enclaves( + this->node_ptr, allocator, &node_names_2, &node_namespaces_2, &node_enclaves); + EXPECT_EQ(RCL_RET_OK, ret); +} From cb9fe4e5b5f505e0798d8b1ca522c6c9c9a5ff01 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 26 Jun 2020 16:11:36 -0300 Subject: [PATCH 03/22] Add tests remap basic usage Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 1 + rcl/test/rcl/test_remap.cpp | 44 +++++++++++++++++++++++++++++++++++++ 2 files changed, 45 insertions(+) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 73e4eda70..31d507313 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -178,6 +178,7 @@ function(test_target_function) SRCS rcl/test_remap.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} + INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ LIBRARIES ${PROJECT_NAME} AMENT_DEPENDENCIES "osrf_testing_tools_cpp" ) diff --git a/rcl/test/rcl/test_remap.cpp b/rcl/test/rcl/test_remap.cpp index 29b41658e..070c2e92c 100644 --- a/rcl/test/rcl/test_remap.cpp +++ b/rcl/test/rcl/test_remap.cpp @@ -14,11 +14,15 @@ #include +#include "rcl/arguments.h" #include "rcl/rcl.h" #include "rcl/remap.h" #include "rcl/error_handling.h" #include "./arg_macros.hpp" +#include "./arguments_impl.h" +#include "./allocator_testing_utils.h" +#include "./remap_impl.h" #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX @@ -536,3 +540,43 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) { EXPECT_EQ(RCL_RET_OK, ret); EXPECT_EQ(NULL, output); } + +TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), internal_remap_use) { + // Easiest way to init a rcl_remap is through the arguments API + const char * argv[] = { + "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg" + }; + int argc = sizeof(argv) / sizeof(const char *); + rcl_allocator_t alloc = rcl_get_default_allocator(); + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + + rcl_ret_t ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( + { + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); + }); + + // Bad alloc + rcl_remap_t remap_dst = rcl_get_zero_initialized_remap(); + parsed_args.impl->remap_rules->impl->allocator = get_failing_allocator(); + EXPECT_EQ(RCL_RET_BAD_ALLOC, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); + parsed_args.impl->remap_rules->impl->allocator = alloc; + + // Expected usage + EXPECT_EQ(RCL_RET_OK, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); + + // Copy twice + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); + rcl_reset_error(); + + // Fini + EXPECT_EQ(RCL_RET_OK, rcl_remap_fini(&remap_dst)); + + // Fini twice + EXPECT_EQ(RCL_RET_ERROR, rcl_remap_fini(&remap_dst)); + rcl_reset_error(); + + // Bad fini + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_remap_fini(nullptr)); +} From cc6c7bb400b7c4656f98929e03e7361d229321b9 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 26 Jun 2020 17:28:17 -0300 Subject: [PATCH 04/22] Add more tests remap module Signed-off-by: Jorge Perez --- rcl/test/rcl/test_remap.cpp | 35 +++++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/rcl/test/rcl/test_remap.cpp b/rcl/test/rcl/test_remap.cpp index 070c2e92c..d22d9454b 100644 --- a/rcl/test/rcl/test_remap.cpp +++ b/rcl/test/rcl/test_remap.cpp @@ -580,3 +580,38 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), internal_remap_use) { // Bad fini EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_remap_fini(nullptr)); } + + +TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), _rcl_remap_name_bad_arg) { + rcl_arguments_t global_arguments; + SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__node:=global_name"); + rcl_arguments_t local_arguments; + SCOPE_ARGS(local_arguments, "process_name", "--ros-args", "-r", "__node:=local_name"); + rcl_arguments_t zero_init_global_arguments = rcl_get_zero_initialized_arguments(); + rcl_allocator_t allocator = rcl_get_default_allocator(); + rcl_allocator_t bad_allocator = get_failing_allocator(); + char * output = NULL; + + // Expected usage local_args, global not init is OK + rcl_ret_t ret = rcl_remap_node_name( + &local_arguments, &zero_init_global_arguments, "NodeName", allocator, &output); + EXPECT_EQ(RCL_RET_OK, ret); + EXPECT_STREQ("local_name", output); + allocator.deallocate(output, allocator.state); + + // Expected usage global_args, local not null is OK + ret = rcl_remap_node_name(nullptr, &global_arguments, "NodeName", allocator, &output); + EXPECT_EQ(RCL_RET_OK, ret); + EXPECT_STREQ("global_name", output); + allocator.deallocate(output, allocator.state); + + // Both local and global arguments, not valid + ret = rcl_remap_node_name(nullptr, nullptr, "NodeName", allocator, &output); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + rcl_reset_error(); + + // Bad allocator + ret = rcl_remap_node_name(nullptr, &global_arguments, "NodeName", bad_allocator, &output); + EXPECT_EQ(RCL_RET_ERROR, ret); + rcl_reset_error(); +} From a3548ab9b73547bb49b733b92fb7cab831724a5d Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Mon, 29 Jun 2020 17:34:03 -0300 Subject: [PATCH 05/22] Add tests ini/fini publisher_node Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 2 +- rcl/test/rcl/test_logging_rosout.cpp | 40 ++++++++++++++++++++++++++++ 2 files changed, 41 insertions(+), 1 deletion(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 31d507313..cc29e1baa 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -263,7 +263,7 @@ function(test_target_function) ) rcl_add_custom_gtest(test_logging_rosout${target_suffix} - SRCS rcl/test_logging_rosout.cpp + SRCS rcl/test_logging_rosout.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/logging_rosout.c ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} diff --git a/rcl/test/rcl/test_logging_rosout.cpp b/rcl/test/rcl/test_logging_rosout.cpp index 8816a55a9..94f9efb29 100644 --- a/rcl/test/rcl/test_logging_rosout.cpp +++ b/rcl/test/rcl/test_logging_rosout.cpp @@ -25,6 +25,8 @@ #include "rcl_interfaces/msg/log.h" #include "rcutils/logging_macros.h" +#include "rcl/logging_rosout.h" + #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX # define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) @@ -63,6 +65,8 @@ std::ostream & operator<<( return out; } +class CLASSNAME (TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION) : public ::testing::Test {}; + class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture) : public ::testing::TestWithParam { @@ -272,3 +276,39 @@ INSTANTIATE_TEST_CASE_P_RMW( TestLoggingRosoutFixture, ::testing::ValuesIn(get_parameters()), ::testing::PrintToStringParamName()); + +/* Testing twice init logging_rosout + */ +TEST_F( + CLASSNAME(TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION), test_twice_init_logging_rosout) { + rcl_allocator_t allocator = rcl_get_default_allocator(); + EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); + + // Init twice returns RCL_RET_OK + EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); + + EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_fini()); +} + +/* Bad params + */ +TEST_F( + CLASSNAME( + TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION), + test_bad_params_init_fini_node_publisher) { + rcl_allocator_t allocator = rcl_get_default_allocator(); + rcl_node_t not_init_node = rcl_get_zero_initialized_node(); + EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); + + EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_logging_rosout_init_publisher_for_node(nullptr)); + rcl_reset_error(); + EXPECT_EQ(RCL_RET_ERROR, rcl_logging_rosout_init_publisher_for_node(¬_init_node)); + rcl_reset_error(); + + EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_logging_rosout_fini_publisher_for_node(nullptr)); + rcl_reset_error(); + EXPECT_EQ(RCL_RET_ERROR, rcl_logging_rosout_fini_publisher_for_node(¬_init_node)); + rcl_reset_error(); + + EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_fini()); +} From afbcbb9a00c7ae8933eb86e2af2b849e107aa446 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Mon, 29 Jun 2020 18:38:06 -0300 Subject: [PATCH 06/22] Refactor style and naming Signed-off-by: Jorge Perez --- rcl/test/rcl/test_logging_rosout.cpp | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/rcl/test/rcl/test_logging_rosout.cpp b/rcl/test/rcl/test_logging_rosout.cpp index 94f9efb29..e8a6d5fd0 100644 --- a/rcl/test/rcl/test_logging_rosout.cpp +++ b/rcl/test/rcl/test_logging_rosout.cpp @@ -65,7 +65,7 @@ std::ostream & operator<<( return out; } -class CLASSNAME (TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION) : public ::testing::Test {}; +class CLASSNAME (TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION) : public ::testing::Test {}; class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture) : public ::testing::TestWithParam @@ -280,7 +280,8 @@ INSTANTIATE_TEST_CASE_P_RMW( /* Testing twice init logging_rosout */ TEST_F( - CLASSNAME(TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION), test_twice_init_logging_rosout) { + CLASSNAME(TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION), test_twice_init_logging_rosout) +{ rcl_allocator_t allocator = rcl_get_default_allocator(); EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); @@ -294,8 +295,9 @@ TEST_F( */ TEST_F( CLASSNAME( - TestLoggingRosoutFixtureNotParam, RMW_IMPLEMENTATION), - test_bad_params_init_fini_node_publisher) { + TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION), + test_bad_params_init_fini_node_publisher) +{ rcl_allocator_t allocator = rcl_get_default_allocator(); rcl_node_t not_init_node = rcl_get_zero_initialized_node(); EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); From dfb9597a7787b9f7912a88d7da92fc6c4404fe37 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Mon, 29 Jun 2020 19:48:36 -0300 Subject: [PATCH 07/22] Add nullptr bad arg Signed-off-by: Jorge Perez --- rcl/test/rcl/test_security.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/rcl/test/rcl/test_security.cpp b/rcl/test/rcl/test_security.cpp index 85aa9ba2e..9fbf28d67 100644 --- a/rcl/test/rcl/test_security.cpp +++ b/rcl/test/rcl/test_security.cpp @@ -121,6 +121,11 @@ class TestGetSecureRoot : public ::testing::Test }; TEST_F(TestGetSecureRoot, failureScenarios) { + EXPECT_EQ( + rcl_get_secure_root(nullptr, &allocator), + (char *) NULL); + rcl_reset_error(); + EXPECT_EQ( rcl_get_secure_root(TEST_ENCLAVE_ABSOLUTE, &allocator), (char *) NULL); From 0dc75ea0094ed0b45c1b91fdacfab7ccdb3631c8 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 30 Jun 2020 17:46:32 -0300 Subject: [PATCH 08/22] Add tests bad args Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 1 + rcl/test/rcl/test_arguments.cpp | 84 +++++++++++++++++++++++++++++++++ 2 files changed, 85 insertions(+) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index cc29e1baa..a54f5e8a8 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -170,6 +170,7 @@ function(test_target_function) SRCS rcl/test_arguments.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} + INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ LIBRARIES ${PROJECT_NAME} osrf_testing_tools_cpp::memory_tools AMENT_DEPENDENCIES "osrf_testing_tools_cpp" "rcpputils" ) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 5636a5486..9344b050f 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -26,6 +26,9 @@ #include "rcl_yaml_param_parser/parser.h" +#include "./allocator_testing_utils.h" +#include "./arguments_impl.h" + #ifdef RMW_IMPLEMENTATION # define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX # define CLASSNAME(NAME, SUFFIX) CLASSNAME_(NAME, SUFFIX) @@ -281,6 +284,61 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args) { rcl_reset_error(); } +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_negative_args) { + int argc = -1; + const char * argv[] = {"process_name"}; + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse_args) { + const char * argv[] = {"process_name"}; + int argc = sizeof(argv) / sizeof(const char *); + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + rcl_allocator_t bad_alloc = get_failing_allocator(); + rcl_ret_t ret = rcl_parse_arguments(argc, argv, bad_alloc, &parsed_args); + EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str; + rcl_reset_error(); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_unparse_args) { + const char * argv[] = { + "process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"}; + int argc = sizeof(argv) / sizeof(const char *); + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + rcl_allocator_t bad_alloc = get_failing_allocator(); + rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + EXPECT_EQ(2, rcl_arguments_get_count_unparsed(&parsed_args)); + + int * actual_unparsed = NULL; + EXPECT_EQ( + RCL_RET_BAD_ALLOC, rcl_arguments_get_unparsed(&parsed_args, bad_alloc, &actual_unparsed)); + rcl_reset_error(); + EXPECT_EQ( + RCL_RET_BAD_ALLOC, rcl_arguments_get_unparsed_ros(&parsed_args, bad_alloc, &actual_unparsed)); + rcl_reset_error(); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_params_get_counts) { + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + EXPECT_EQ(-1, rcl_arguments_get_count_unparsed(nullptr)); + rcl_reset_error(); + EXPECT_EQ(-1, rcl_arguments_get_count_unparsed_ros(nullptr)); + rcl_reset_error(); + EXPECT_EQ(-1, rcl_arguments_get_param_files_count(nullptr)); + rcl_reset_error(); + EXPECT_EQ(-1, rcl_arguments_get_count_unparsed(&parsed_args)); + rcl_reset_error(); + EXPECT_EQ(-1, rcl_arguments_get_count_unparsed_ros(&parsed_args)); + rcl_reset_error(); + EXPECT_EQ(-1, rcl_arguments_get_param_files_count(&parsed_args)); + rcl_reset_error(); + rcl_reset_error(); +} + TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_output) { const char * argv[] = {"process_name"}; int argc = sizeof(argv) / sizeof(const char *); @@ -402,6 +460,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) { ret = rcl_arguments_copy(&parsed_args, &copied_args); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + // Can't copy to non empty + ret = rcl_arguments_copy(&parsed_args, &copied_args); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; + rcl_reset_error(); + EXPECT_UNPARSED(parsed_args, 0, 8); EXPECT_UNPARSED_ROS(parsed_args, 2); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); @@ -411,6 +474,27 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) { EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&copied_args)); } +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) { + const char * argv[] = {"process_name", "--ros-args", "/foo/bar:="}; + int argc = sizeof(argv) / sizeof(const char *); + rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); + rcl_ret_t ret; + + ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); + EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + + rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments(); + rcl_allocator_t bad_alloc = get_failing_allocator(); + rcl_allocator_t * saved_alloc = &parsed_args.impl->allocator; + parsed_args.impl->allocator = bad_alloc; + ret = rcl_arguments_copy(&parsed_args, &copied_args); + EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str; + rcl_reset_error(); + parsed_args.impl->allocator = *saved_alloc; + + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); +} + TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_ros_args) { const char * argv[] = {"process_name", "--ros-args", "--", "arg", "--ros-args"}; int argc = sizeof(argv) / sizeof(const char *); From 42e3835dcb97fd996611d0fe54c55c5b35dabb3f Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 30 Jun 2020 18:08:45 -0300 Subject: [PATCH 09/22] Add test bad_alloc Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 9344b050f..af66614e7 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -649,6 +649,12 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_remove_ros_ argv, &parsed_args, zero_initialized_allocator, &nonros_argc, &nonros_argv)); rcl_reset_error(); + rcl_allocator_t bad_alloc = get_failing_allocator(); + EXPECT_EQ( + RCL_RET_BAD_ALLOC, rcl_remove_ros_arguments( + argv, &parsed_args, bad_alloc, &nonros_argc, &nonros_argv)); + rcl_reset_error(); + EXPECT_EQ( RCL_RET_INVALID_ARGUMENT, rcl_remove_ros_arguments( argv, &parsed_args, default_allocator, NULL, &nonros_argv)); From 21bc3c5d114b313e6fa4e9bc0351fd2153809b8a Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 30 Jun 2020 18:41:03 -0300 Subject: [PATCH 10/22] Add missing source file Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index a54f5e8a8..dcda50e52 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -176,7 +176,7 @@ function(test_target_function) ) rcl_add_custom_gtest(test_remap${target_suffix} - SRCS rcl/test_remap.cpp + SRCS rcl/test_remap.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/remap.c ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ From 1cf8153875fdfb143ab2c969de36910097e9251b Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 1 Jul 2020 17:25:45 -0300 Subject: [PATCH 11/22] Remove not working test Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 2 +- rcl/test/rcl/test_logging_rosout.cpp | 24 ------------------------ 2 files changed, 1 insertion(+), 25 deletions(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index dcda50e52..b30e1d98a 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -264,7 +264,7 @@ function(test_target_function) ) rcl_add_custom_gtest(test_logging_rosout${target_suffix} - SRCS rcl/test_logging_rosout.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/logging_rosout.c + SRCS rcl/test_logging_rosout.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} LIBRARIES ${PROJECT_NAME} diff --git a/rcl/test/rcl/test_logging_rosout.cpp b/rcl/test/rcl/test_logging_rosout.cpp index e8a6d5fd0..ac2020ad6 100644 --- a/rcl/test/rcl/test_logging_rosout.cpp +++ b/rcl/test/rcl/test_logging_rosout.cpp @@ -290,27 +290,3 @@ TEST_F( EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_fini()); } - -/* Bad params - */ -TEST_F( - CLASSNAME( - TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION), - test_bad_params_init_fini_node_publisher) -{ - rcl_allocator_t allocator = rcl_get_default_allocator(); - rcl_node_t not_init_node = rcl_get_zero_initialized_node(); - EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_init(&allocator)); - - EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_logging_rosout_init_publisher_for_node(nullptr)); - rcl_reset_error(); - EXPECT_EQ(RCL_RET_ERROR, rcl_logging_rosout_init_publisher_for_node(¬_init_node)); - rcl_reset_error(); - - EXPECT_EQ(RCL_RET_NODE_INVALID, rcl_logging_rosout_fini_publisher_for_node(nullptr)); - rcl_reset_error(); - EXPECT_EQ(RCL_RET_ERROR, rcl_logging_rosout_fini_publisher_for_node(¬_init_node)); - rcl_reset_error(); - - EXPECT_EQ(RCL_RET_OK, rcl_logging_rosout_fini()); -} From 3c202f6fd266efbda33ba2daa4be270158ad925e Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 1 Jul 2020 20:27:04 -0300 Subject: [PATCH 12/22] Remove extra rcl_reset_error Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index af66614e7..4d82f8dce 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -336,7 +336,6 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_params_get_ rcl_reset_error(); EXPECT_EQ(-1, rcl_arguments_get_param_files_count(&parsed_args)); rcl_reset_error(); - rcl_reset_error(); } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_output) { From 967b2a70275ee507dc532af0da55a54947ee6187 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Wed, 1 Jul 2020 20:28:16 -0300 Subject: [PATCH 13/22] Change ASSERT to EXPECT when fini scope Signed-off-by: Jorge Perez --- rcl/test/rcl/test_graph.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 7ef863094..56787ff66 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -1432,11 +1432,11 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( { ret = rcutils_string_array_fini(&node_names); - ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(RCUTILS_RET_OK, ret); ret = rcutils_string_array_fini(&node_namespaces); - ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(RCUTILS_RET_OK, ret); ret = rcutils_string_array_fini(&node_enclaves); - ASSERT_EQ(RCUTILS_RET_OK, ret); + EXPECT_EQ(RCUTILS_RET_OK, ret); }); rcl_allocator_t allocator = rcl_get_default_allocator(); From 583d23b80d517250d8fee5aeb363ba1cd8eac048 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 2 Jul 2020 17:32:58 -0300 Subject: [PATCH 14/22] Add const for const arguments Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 110 ++++++++++++++++---------------- 1 file changed, 55 insertions(+), 55 deletions(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 4d82f8dce..35d562820 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -277,7 +277,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_args) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args) { - int argc = 1; + const int argc = 1; rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret = rcl_parse_arguments(argc, NULL, rcl_get_default_allocator(), &parsed_args); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; @@ -285,8 +285,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_negative_args) { - int argc = -1; - const char * argv[] = {"process_name"}; + const int argc = -1; + const char * const argv[] = {"process_name"}; rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; @@ -294,8 +294,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_negative_args) } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse_args) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_allocator_t bad_alloc = get_failing_allocator(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, bad_alloc, &parsed_args); @@ -304,9 +304,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_unparse_args) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"}; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_allocator_t bad_alloc = get_failing_allocator(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -339,16 +339,16 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_params_get_ } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_args_output) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), NULL); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret) << rcl_get_error_string().str; rcl_reset_error(); } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_ros_args) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -358,8 +358,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_ros_args) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args) { - const char * argv[] = {"process_name", "--ros-args"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -369,8 +369,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args) } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args_w_trailing_dashes) { - const char * argv[] = {"process_name", "--ros-args", "--"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "--"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; @@ -380,10 +380,10 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_zero_ros_args_w } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remap) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--remap", "foo:=/baz" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -394,8 +394,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remap) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_two_ros_args) { - const char * argv[] = {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -406,8 +406,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_two_r } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_trailing_dashes) { - const char * argv[] = {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -418,8 +418,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_tra } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_two_trailing_dashes) { - const char * argv[] = {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -430,10 +430,10 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_two } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_mix_valid_invalid_rules) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -444,11 +444,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_mix_valid_inval } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "-r", "__ns:=/foo", "--", "arg" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -474,8 +474,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) { - const char * argv[] = {"process_name", "--ros-args", "/foo/bar:="}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "/foo/bar:="}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -495,8 +495,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_ros_args) { - const char * argv[] = {"process_name", "--ros-args", "--", "arg", "--ros-args"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "--", "arg", "--ros-args"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -549,10 +549,10 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_args) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_namespace) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "-r", "__ns:=/foo/bar", "-r", "__ns:=/fiz/buz" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); @@ -563,8 +563,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_two_namespace) } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_uninitialized_parsed_args) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args; int not_null = 1; parsed_args.impl = reinterpret_cast(¬_null); @@ -575,10 +575,10 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_uninitialized_p } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_double_parse) { - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "-r", "__ns:=/foo/bar", "-r", "__ns:=/fiz/buz" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); ASSERT_EQ( RCL_RET_OK, @@ -606,8 +606,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_impl_null) } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_twice) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); ASSERT_EQ(RCL_RET_OK, rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args)); EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); @@ -616,8 +616,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_fini_twice) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_remove_ros_args) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t default_allocator = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -695,11 +695,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_remove_ros_ } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args) { - const char * argv[] = { + const char * const argv[] = { "process_name", "-d", "--ros-args", "-r", "__ns:=/foo/bar", "-r", "__ns:=/fiz/buz", "--", "--foo=bar", "--baz", "--ros-args", "--ros-args", "-p", "bar:=baz", "--", "--", "arg", }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -735,8 +735,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args_if_ros_only) { - const char * argv[] = {"--ros-args", "--disable-rosout-logs"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"--ros-args", "--disable-rosout-logs"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -802,8 +802,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) { - const char * argv[] = {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -821,11 +821,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_single) { const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string(); - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg", "--params-file", parameters_filepath.c_str() }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -873,11 +873,11 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_multiple) { const std::string parameters_filepath1 = (test_path / "test_parameters.1.yaml").string(); const std::string parameters_filepath2 = (test_path / "test_parameters.2.yaml").string(); - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "--params-file", parameters_filepath1.c_str(), "-r", "__ns:=/namespace", "random:=arg", "--params-file", parameters_filepath2.c_str() }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_ret_t ret; rcl_allocator_t alloc = rcl_get_default_allocator(); @@ -939,8 +939,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_ } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overrides) { - const char * argv[] = {"process_name"}; - int argc = sizeof(argv) / sizeof(const char *); + const char * const argv[] = {"process_name"}; + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); @@ -975,14 +975,14 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overri TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_overrides) { const std::string parameters_filepath = (test_path / "test_parameters.1.yaml").string(); - const char * argv[] = { + const char * const argv[] = { "process_name", "--ros-args", "--params-file", parameters_filepath.c_str(), "--param", "string_param:=bar", "-p", "some.bool_param:=false", "-p", "some_node:int_param:=4" }; - int argc = sizeof(argv) / sizeof(const char *); + const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); From 9d8867a69b3a8bf381faef5fbc55666fd721b9b9 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 2 Jul 2020 17:34:54 -0300 Subject: [PATCH 15/22] Add missing fini parsed arguments Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 35d562820..746bd25d0 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -310,7 +310,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_unpar rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_allocator_t bad_alloc = get_failing_allocator(); rcl_ret_t ret = rcl_parse_arguments(argc, argv, rcl_get_default_allocator(), &parsed_args); - EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; + ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; EXPECT_EQ(2, rcl_arguments_get_count_unparsed(&parsed_args)); int * actual_unparsed = NULL; @@ -320,6 +320,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_unpar EXPECT_EQ( RCL_RET_BAD_ALLOC, rcl_arguments_get_unparsed_ros(&parsed_args, bad_alloc, &actual_unparsed)); rcl_reset_error(); + + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_params_get_counts) { From f26e72f079ae0dae5a0daf3b8717ad83d92a8753 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 2 Jul 2020 17:38:59 -0300 Subject: [PATCH 16/22] Add error string to output Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 746bd25d0..18a1c0f49 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -493,7 +493,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) rcl_reset_error(); parsed_args.impl->allocator = *saved_alloc; - EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)) << rcl_get_error_string().str; } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_no_ros_args) { From 78b4929851b0dadba822be24dd05b7ce6710d74f Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 2 Jul 2020 18:00:34 -0300 Subject: [PATCH 17/22] Add invalid usage comments to test Signed-off-by: Jorge Perez --- rcl/test/rcl/test_graph.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index 56787ff66..6d8d83a2f 100644 --- a/rcl/test/rcl/test_graph.cpp +++ b/rcl/test/rcl/test_graph.cpp @@ -1440,6 +1440,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) }); rcl_allocator_t allocator = rcl_get_default_allocator(); + // Invalid nullptr as node ret = rcl_get_node_names(nullptr, allocator, &node_names, &node_namespaces); EXPECT_EQ(RCL_RET_NODE_INVALID, ret); rcl_reset_error(); @@ -1448,6 +1449,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) EXPECT_EQ(RCL_RET_NODE_INVALID, ret); rcl_reset_error(); + // Invalid not init node rcl_node_t not_init_node = rcl_get_zero_initialized_node(); ret = rcl_get_node_names(¬_init_node, allocator, &node_names, &node_namespaces); EXPECT_EQ(RCL_RET_NODE_INVALID, ret); @@ -1457,6 +1459,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) EXPECT_EQ(RCL_RET_NODE_INVALID, ret); rcl_reset_error(); + // Invalid nullptr as node names output ret = rcl_get_node_names(this->node_ptr, allocator, nullptr, &node_namespaces); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ret = rcl_get_node_names_with_enclaves( @@ -1464,6 +1467,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); + // Invalid nullptr as node_namespaces output ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); ret = rcl_get_node_names_with_enclaves( @@ -1471,11 +1475,13 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); + // Invalid nullptr as node_enclaves output ret = rcl_get_node_names_with_enclaves( this->node_ptr, allocator, &node_names, &node_namespaces, nullptr); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); rcl_reset_error(); + // Invalid node_names previously init (size is set) node_names.size = 1; ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); @@ -1485,6 +1491,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) rcl_reset_error(); node_names.size = 0; + // Invalid node_names previously init (size is zero, but internal structure size is 1) ret = rcutils_string_array_init(&node_names, 1, &allocator); EXPECT_EQ(RCL_RET_OK, ret); node_names.size = 0; @@ -1498,6 +1505,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) ret = rcutils_string_array_fini(&node_names); EXPECT_EQ(RCL_RET_OK, ret); + // Invalid node_namespaces previously init (size is set) node_namespaces.size = 1; ret = rcl_get_node_names(this->node_ptr, allocator, &node_names, &node_namespaces); EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); @@ -1507,6 +1515,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) rcl_reset_error(); node_namespaces.size = 0; + // Invalid node_namespaces previously init (size is zero, but internal structure size is 1) ret = rcutils_string_array_init(&node_namespaces, 1, &allocator); EXPECT_EQ(RCL_RET_OK, ret); node_namespaces.size = 0; @@ -1520,6 +1529,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) ret = rcutils_string_array_fini(&node_namespaces); EXPECT_EQ(RCL_RET_OK, ret); + // Invalid node_enclaves previously init (size is set) node_enclaves.size = 1; ret = rcl_get_node_names_with_enclaves( this->node_ptr, allocator, &node_names, &node_namespaces, &node_enclaves); @@ -1527,6 +1537,7 @@ TEST_F(CLASSNAME(TestGraphFixture, RMW_IMPLEMENTATION), test_bad_get_node_names) rcl_reset_error(); node_enclaves.size = 0; + // Invalid node_enclave previously init (size is zero, but internal structure size is 1) ret = rcutils_string_array_init(&node_enclaves, 1, &allocator); EXPECT_EQ(RCL_RET_OK, ret); node_enclaves.size = 0; From 2de21076503ae69fcb5cb981a80435df5b8e8196 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Thu, 2 Jul 2020 18:06:11 -0300 Subject: [PATCH 18/22] Fix lint line length issues Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 18a1c0f49..374d0f8c8 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -396,7 +396,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remap) { } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_two_ros_args) { - const char * const argv[] = {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; + const char * const argv[] = + {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -420,7 +421,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_tra } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_two_trailing_dashes) { - const char * const argv[] = {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; + const char * const argv[] = + {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -804,7 +806,8 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args } TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) { - const char * const argv[] = {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; + const char * const argv[] = + {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); From 8a1522a2ceb81b44d1f91aa429b639bb4c16bf90 Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 3 Jul 2020 10:36:06 -0300 Subject: [PATCH 19/22] Fix uncrustify lint Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 374d0f8c8..3f605183d 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -397,7 +397,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remap) { TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_two_ros_args) { const char * const argv[] = - {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; + {"process_name", "--ros-args", "--ros-args", "-r", "/foo/bar:=/fiz/buz"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -422,7 +422,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_tra TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_one_remap_w_two_trailing_dashes) { const char * const argv[] = - {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; + {"process_name", "--ros-args", "-r", "/foo/bar:=/fiz/buz", "--", "--"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); rcl_ret_t ret; @@ -807,7 +807,7 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_remove_ros_args TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_argument_zero) { const char * const argv[] = - {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; + {"process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg"}; const int argc = sizeof(argv) / sizeof(const char *); rcl_allocator_t alloc = rcl_get_default_allocator(); From ecce49ae78aed9ed811db4e722be73acd76e7f0b Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Fri, 3 Jul 2020 17:52:40 -0300 Subject: [PATCH 20/22] Modify test to save alloc struct Signed-off-by: Jorge Perez --- rcl/test/rcl/test_arguments.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/rcl/test/rcl/test_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 3f605183d..c723eb523 100644 --- a/rcl/test/rcl/test_arguments.cpp +++ b/rcl/test/rcl/test_arguments.cpp @@ -488,12 +488,12 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_bad_alloc) rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments(); rcl_allocator_t bad_alloc = get_failing_allocator(); - rcl_allocator_t * saved_alloc = &parsed_args.impl->allocator; + rcl_allocator_t saved_alloc = parsed_args.impl->allocator; parsed_args.impl->allocator = bad_alloc; ret = rcl_arguments_copy(&parsed_args, &copied_args); EXPECT_EQ(RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string().str; rcl_reset_error(); - parsed_args.impl->allocator = *saved_alloc; + parsed_args.impl->allocator = saved_alloc; EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)) << rcl_get_error_string().str; } From 2c75c605fcbb2d5bfc3a50966eec9f3d48d0d4ca Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 7 Jul 2020 14:37:11 -0300 Subject: [PATCH 21/22] Remove internal source file Signed-off-by: Jorge Perez --- rcl/test/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index b30e1d98a..bf8a2d810 100644 --- a/rcl/test/CMakeLists.txt +++ b/rcl/test/CMakeLists.txt @@ -176,7 +176,7 @@ function(test_target_function) ) rcl_add_custom_gtest(test_remap${target_suffix} - SRCS rcl/test_remap.cpp ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/remap.c + SRCS rcl/test_remap.cpp ENV ${rmw_implementation_env_var} APPEND_LIBRARY_DIRS ${extra_lib_dirs} INCLUDE_DIRS ${CMAKE_CURRENT_SOURCE_DIR}/../src/rcl/ From 897a4089d34432e85cc4b269e53238972431925a Mon Sep 17 00:00:00 2001 From: Jorge Perez Date: Tue, 7 Jul 2020 18:04:13 -0300 Subject: [PATCH 22/22] Remove case requiring internal def Signed-off-by: Jorge Perez --- rcl/test/rcl/test_remap.cpp | 41 ------------------------------------- 1 file changed, 41 deletions(-) diff --git a/rcl/test/rcl/test_remap.cpp b/rcl/test/rcl/test_remap.cpp index d22d9454b..1b0d2eb0e 100644 --- a/rcl/test/rcl/test_remap.cpp +++ b/rcl/test/rcl/test_remap.cpp @@ -541,47 +541,6 @@ TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), url_scheme_rostopic) { EXPECT_EQ(NULL, output); } -TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), internal_remap_use) { - // Easiest way to init a rcl_remap is through the arguments API - const char * argv[] = { - "process_name", "--ros-args", "-r", "__ns:=/namespace", "random:=arg" - }; - int argc = sizeof(argv) / sizeof(const char *); - rcl_allocator_t alloc = rcl_get_default_allocator(); - rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments(); - - rcl_ret_t ret = rcl_parse_arguments(argc, argv, alloc, &parsed_args); - ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str; - OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( - { - EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); - }); - - // Bad alloc - rcl_remap_t remap_dst = rcl_get_zero_initialized_remap(); - parsed_args.impl->remap_rules->impl->allocator = get_failing_allocator(); - EXPECT_EQ(RCL_RET_BAD_ALLOC, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); - parsed_args.impl->remap_rules->impl->allocator = alloc; - - // Expected usage - EXPECT_EQ(RCL_RET_OK, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); - - // Copy twice - EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_remap_copy(parsed_args.impl->remap_rules, &remap_dst)); - rcl_reset_error(); - - // Fini - EXPECT_EQ(RCL_RET_OK, rcl_remap_fini(&remap_dst)); - - // Fini twice - EXPECT_EQ(RCL_RET_ERROR, rcl_remap_fini(&remap_dst)); - rcl_reset_error(); - - // Bad fini - EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_remap_fini(nullptr)); -} - - TEST_F(CLASSNAME(TestRemapFixture, RMW_IMPLEMENTATION), _rcl_remap_name_bad_arg) { rcl_arguments_t global_arguments; SCOPE_ARGS(global_arguments, "process_name", "--ros-args", "-r", "__node:=global_name");