2626
2727#include " rcl_yaml_param_parser/parser.h"
2828
29+ #include " rcutils/testing/fault_injection.h"
30+
2931#include " ./allocator_testing_utils.h"
3032#include " ./arguments_impl.h"
3133
@@ -227,21 +229,18 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_inval
227229
228230 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" }));
229231 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --remap" }));
230-
232+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " :" }));
233+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " 1" }));
234+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " ~" }));
231235 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " :=" }));
232236 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " foo:=" }));
233237 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " :=bar" }));
234-
235- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" }));
236- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --params-file" }));
237-
238- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :=" }));
239- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " foo:=" }));
240- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :=bar" }));
241- EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " __ns:=" }));
242-
238+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " ::=" }));
239+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " 1:=" }));
240+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " ~:=" }));
243241 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " __node:=" }));
244242 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " __node:=/foo/bar" }));
243+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " __ns:=" }));
245244 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " __ns:=foo" }));
246245 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " :__node:=nodename" }));
247246 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " ~:__node:=nodename" }));
@@ -254,11 +253,31 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), check_valid_vs_inval
254253 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " rostopic://:=rosservice" }));
255254 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -r" , " rostopic::=rosservice" }));
256255
256+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" }));
257+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :=" }));
258+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " foo:=" }));
259+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :=bar" }));
260+
261+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :" }));
262+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " 1" }));
263+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " ~" }));
264+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " ::=" }));
265+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " 1:=" }));
266+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " ~:=" }));
267+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " __node:=" }));
268+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " __node:=/foo/bar" }));
269+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " __ns:=foo" }));
270+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " :__node:=nodename" }));
271+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " ~:__node:=nodename" }));
272+
257273 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " }foo:=/bar" }));
258274 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --param" , " }foo:=/bar" }));
259275 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -p" , " f oo:=/bar" }));
260276 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --param" , " f oo:=/bar" }));
261277
278+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " -e" }));
279+ EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --enclave" }));
280+
262281 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --params-file" }));
263282
264283 EXPECT_FALSE (are_valid_ros_args ({" --ros-args" , " --log-config-file" }));
@@ -1032,8 +1051,9 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_param_arguments
10321051
10331052 rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments ();
10341053 ret = rcl_arguments_copy (&parsed_args, &copied_args);
1035- EXPECT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
1054+ ASSERT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
10361055 EXPECT_EQ (2 , rcl_arguments_get_param_files_count (&copied_args));
1056+ EXPECT_EQ (RCL_RET_OK, rcl_arguments_fini (&copied_args));
10371057}
10381058
10391059TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_no_param_overrides) {
@@ -1164,40 +1184,6 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_get_p
11641184 EXPECT_EQ (RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string ().str ;
11651185}
11661186
1167- TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_allocs_copy) {
1168- const std::string parameters_filepath1 = (test_path / " test_parameters.1.yaml" ).string ();
1169- const std::string parameters_filepath2 = (test_path / " test_parameters.2.yaml" ).string ();
1170- const char * const argv[] = {
1171- " process_name" , " --ros-args" , " --params-file" , parameters_filepath1.c_str (),
1172- " -r" , " __ns:=/namespace" , " random:=arg" , " --params-file" , parameters_filepath2.c_str (),
1173- " -r" , " /foo/bar:=/fiz/buz" , " --remap" , " foo:=/baz" ,
1174- " -e" , " /foo" , " --" , " foo"
1175- };
1176- const int argc = sizeof (argv) / sizeof (const char *);
1177-
1178- rcl_allocator_t alloc = rcl_get_default_allocator ();
1179- rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments ();
1180-
1181- rcl_ret_t ret = rcl_parse_arguments (argc, argv, alloc, &parsed_args);
1182- ASSERT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
1183- OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT (
1184- {
1185- EXPECT_EQ (RCL_RET_OK, rcl_arguments_fini (&parsed_args));
1186- });
1187-
1188- rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments ();
1189- rcl_allocator_t bomb_alloc = get_time_bombed_allocator ();
1190- rcl_allocator_t saved_alloc = parsed_args.impl ->allocator ;
1191- parsed_args.impl ->allocator = bomb_alloc;
1192- for (int i = 0 ; i < 8 ; i++) {
1193- set_time_bombed_allocator_count (bomb_alloc, i);
1194- ret = rcl_arguments_copy (&parsed_args, &copied_args);
1195- EXPECT_EQ (RCL_RET_BAD_ALLOC, ret) << rcl_get_error_string ().str ;
1196- rcl_reset_error ();
1197- }
1198- parsed_args.impl ->allocator = saved_alloc;
1199- }
1200-
12011187TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_get_param_files) {
12021188 const std::string parameters_filepath1 = (test_path / " test_parameters.1.yaml" ).string ();
12031189 const char * const argv[] = {
@@ -1232,25 +1218,102 @@ TEST_F(CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_null_get_param_
12321218 rcl_reset_error ();
12331219}
12341220
1235- TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_bad_alloc_parse_arg) {
1236- const std::string parameters_filepath1 = (test_path / " test_parameters.1.yaml" ).string ();
1221+ TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_parse_with_internal_errors) {
1222+ const std::string parameters_filepath1 =
1223+ (test_path / " test_parameters.1.yaml" ).string ();
1224+ const std::string parameters_filepath2 =
1225+ (test_path / " test_parameters.2.yaml" ).string ();
12371226 const char * const argv[] = {
1238- " process_name" , " --ros-args" , " --params-file" , parameters_filepath1.c_str ()
1227+ " process_name" , RCL_ROS_ARGS_FLAG,
1228+ RCL_PARAM_FILE_FLAG, parameters_filepath1.c_str (),
1229+ RCL_REMAP_FLAG, " that_node:foo:=baz" ,
1230+ RCL_REMAP_FLAG, " foo:=bar" ,
1231+ RCL_PARAM_FILE_FLAG, parameters_filepath2.c_str (),
1232+ RCL_REMAP_FLAG, " __name:=my_node" ,
1233+ RCL_REMAP_FLAG, " __ns:=/my_ns" ,
1234+ RCL_PARAM_FLAG, " testing:=true" ,
1235+ RCL_PARAM_FLAG, " this_node:constant:=42" ,
1236+ RCL_ENCLAVE_FLAG, " fizz" ,
1237+ RCL_ENCLAVE_FLAG, " buzz" , // override
1238+ RCL_LOG_LEVEL_FLAG, " rcl:=debug" ,
1239+ RCL_EXTERNAL_LOG_CONFIG_FLAG, " flip.txt" ,
1240+ RCL_EXTERNAL_LOG_CONFIG_FLAG, " flop.txt" , // override
1241+ " --enable-" RCL_LOG_STDOUT_FLAG_SUFFIX,
1242+ " --enable-" RCL_LOG_ROSOUT_FLAG_SUFFIX,
1243+ " --disable-" RCL_LOG_EXT_LIB_FLAG_SUFFIX,
1244+ " --not-a-real-ros-flag" , " not-a-real-ros-arg" ,
1245+ RCL_ROS_ARGS_EXPLICIT_END_TOKEN,
1246+ " --some-non-ros-flag" , " some-non-ros-flag"
12391247 };
1240- const int argc = sizeof (argv) / sizeof (const char *);
1248+ const int argc = sizeof (argv) / sizeof (argv[0 ]);
1249+ rcl_allocator_t allocator = rcl_get_default_allocator ();
1250+ rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments ();
1251+ RCUTILS_FAULT_INJECTION_TEST (
1252+ {
1253+ rcl_ret_t ret = rcl_parse_arguments (argc, argv, allocator, &parsed_args);
1254+ if (RCL_RET_OK == ret) {
1255+ int64_t count = rcutils_fault_injection_get_count ();
1256+ rcutils_fault_injection_set_count (RCUTILS_FAULT_INJECTION_NEVER_FAIL);
1257+ ret = rcl_arguments_fini (&parsed_args);
1258+ rcutils_fault_injection_set_count (count);
1259+ EXPECT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
1260+ } else {
1261+ rcl_reset_error ();
1262+ }
1263+ });
1264+ }
1265+
1266+ TEST_F (CLASSNAME(TestArgumentsFixture, RMW_IMPLEMENTATION), test_copy_with_internal_errors) {
1267+ const std::string parameters_filepath1 =
1268+ (test_path / " test_parameters.1.yaml" ).string ();
1269+ const std::string parameters_filepath2 =
1270+ (test_path / " test_parameters.2.yaml" ).string ();
1271+ const char * const argv[] = {
1272+ " process_name" , RCL_ROS_ARGS_FLAG,
1273+ RCL_PARAM_FILE_FLAG, parameters_filepath1.c_str (),
1274+ RCL_REMAP_FLAG, " that_node:foo:=baz" ,
1275+ RCL_REMAP_FLAG, " foo:=bar" ,
1276+ RCL_PARAM_FILE_FLAG, parameters_filepath2.c_str (),
1277+ RCL_REMAP_FLAG, " __name:=my_node" ,
1278+ RCL_REMAP_FLAG, " __ns:=/my_ns" ,
1279+ RCL_PARAM_FLAG, " testing:=true" ,
1280+ RCL_PARAM_FLAG, " this_node:constant:=42" ,
1281+ RCL_ENCLAVE_FLAG, " fizz" ,
1282+ RCL_ENCLAVE_FLAG, " buzz" , // override
1283+ RCL_LOG_LEVEL_FLAG, " rcl:=debug" ,
1284+ RCL_EXTERNAL_LOG_CONFIG_FLAG, " flip.txt" ,
1285+ RCL_EXTERNAL_LOG_CONFIG_FLAG, " flop.txt" , // override
1286+ " --enable-" RCL_LOG_STDOUT_FLAG_SUFFIX,
1287+ " --enable-" RCL_LOG_ROSOUT_FLAG_SUFFIX,
1288+ " --disable-" RCL_LOG_EXT_LIB_FLAG_SUFFIX,
1289+ " --not-a-real-ros-flag" , " not-a-real-ros-arg" ,
1290+ RCL_ROS_ARGS_EXPLICIT_END_TOKEN,
1291+ " --some-non-ros-flag" , " some-non-ros-flag"
1292+ };
1293+ const int argc = sizeof (argv) / sizeof (argv[0 ]);
12411294
1295+ rcl_allocator_t alloc = rcl_get_default_allocator ();
12421296 rcl_arguments_t parsed_args = rcl_get_zero_initialized_arguments ();
1243- rcl_allocator_t bomb_alloc = get_time_bombed_allocator ();
12441297
1245- for (int i = 0 ; i < 100 ; i++) {
1246- set_time_bombed_allocator_count (bomb_alloc, i);
1247- rcl_ret_t ret = rcl_parse_arguments (argc, argv, bomb_alloc, &parsed_args);
1298+ rcl_ret_t ret = rcl_parse_arguments (argc, argv, alloc, &parsed_args);
1299+ ASSERT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
1300+ OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT (
1301+ {
1302+ EXPECT_EQ (RCL_RET_OK, rcl_arguments_fini (&parsed_args));
1303+ });
1304+
1305+ rcl_arguments_t copied_args = rcl_get_zero_initialized_arguments ();
1306+ RCUTILS_FAULT_INJECTION_TEST (
1307+ {
1308+ rcl_ret_t ret = rcl_arguments_copy (&parsed_args, &copied_args);
12481309 if (RCL_RET_OK == ret) {
1249- EXPECT_EQ (RCL_RET_OK, rcl_arguments_fini (&parsed_args));
1250- break ;
1310+ int64_t count = rcutils_fault_injection_get_count ();
1311+ rcutils_fault_injection_set_count (RCUTILS_FAULT_INJECTION_NEVER_FAIL);
1312+ ret = rcl_arguments_fini (&copied_args);
1313+ rcutils_fault_injection_set_count (count);
1314+ EXPECT_EQ (RCL_RET_OK, ret) << rcl_get_error_string ().str ;
12511315 } else {
1252- EXPECT_EQ (RCL_RET_BAD_ALLOC, ret);
12531316 rcl_reset_error ();
12541317 }
1255- }
1318+ });
12561319}
0 commit comments