diff --git a/rcl/test/CMakeLists.txt b/rcl/test/CMakeLists.txt index 73e4eda70..bf8a2d810 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" ) @@ -178,6 +179,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_arguments.cpp b/rcl/test/rcl/test_arguments.cpp index 5636a5486..c723eb523 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) @@ -274,24 +277,80 @@ 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; rcl_reset_error(); } +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_negative_args) { + 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; + rcl_reset_error(); +} + +TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse_args) { + 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); + 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 * const argv[] = { + "process_name", "--ros-args", "/foo/bar:=", "-r", "bar:=/fiz/buz", "}bar:=fiz", "--", "arg"}; + 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); + 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; + 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(); + + EXPECT_EQ(RCL_RET_OK, rcl_arguments_fini(&parsed_args)); +} + +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(); +} + 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; @@ -301,8 +360,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; @@ -312,8 +371,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; @@ -323,10 +382,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); @@ -337,8 +396,9 @@ 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); @@ -349,8 +409,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); @@ -361,8 +421,9 @@ 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); @@ -373,10 +434,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); @@ -387,11 +448,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; @@ -402,6 +463,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,9 +477,30 @@ 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 * 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; + + 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)) << rcl_get_error_string().str; +} + 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; @@ -466,10 +553,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); @@ -480,8 +567,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); @@ -492,10 +579,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, @@ -523,8 +610,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)); @@ -533,8 +620,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(); @@ -565,6 +652,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)); @@ -606,11 +699,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(); @@ -646,8 +739,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(); @@ -713,8 +806,9 @@ 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(); @@ -732,11 +826,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(); @@ -784,11 +878,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(); @@ -850,8 +944,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(); @@ -886,14 +980,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(); diff --git a/rcl/test/rcl/test_graph.cpp b/rcl/test/rcl/test_graph.cpp index d72a08997..6d8d83a2f 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); @@ -1354,3 +1388,171 @@ 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); + EXPECT_EQ(RCUTILS_RET_OK, ret); + ret = rcutils_string_array_fini(&node_namespaces); + EXPECT_EQ(RCUTILS_RET_OK, ret); + ret = rcutils_string_array_fini(&node_enclaves); + EXPECT_EQ(RCUTILS_RET_OK, ret); + }); + 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(); + 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(); + + // 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); + 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(); + + // 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( + this->node_ptr, allocator, nullptr, &node_namespaces, &node_enclaves); + 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( + this->node_ptr, allocator, &node_names, nullptr, &node_enclaves); + 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); + 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; + + // 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; + 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); + + // 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); + 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; + + // 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; + 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); + + // 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); + EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret); + 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; + 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); +} diff --git a/rcl/test/rcl/test_logging_rosout.cpp b/rcl/test/rcl/test_logging_rosout.cpp index 8816a55a9..ac2020ad6 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 (TestLogRosoutFixtureNotParam, RMW_IMPLEMENTATION) : public ::testing::Test {}; + class TEST_FIXTURE_P_RMW (TestLoggingRosoutFixture) : public ::testing::TestWithParam { @@ -272,3 +276,17 @@ INSTANTIATE_TEST_CASE_P_RMW( TestLoggingRosoutFixture, ::testing::ValuesIn(get_parameters()), ::testing::PrintToStringParamName()); + +/* Testing twice init logging_rosout + */ +TEST_F( + 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)); + + // 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()); +} diff --git a/rcl/test/rcl/test_remap.cpp b/rcl/test/rcl/test_remap.cpp index 29b41658e..1b0d2eb0e 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,37 @@ 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), _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(); +} 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);