ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
arguments.c
1 // Copyright 2018 Open Source Robotics Foundation, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
16 
17 #include "rcl/arguments.h"
18 
19 #include <assert.h>
20 #include <string.h>
21 
22 #include "./arguments_impl.h"
23 #include "./remap_impl.h"
24 #include "rcl/error_handling.h"
25 #include "rcl/lexer_lookahead.h"
27 #include "rcl_yaml_param_parser/parser.h"
28 #include "rcl_yaml_param_parser/types.h"
29 #include "rcutils/allocator.h"
30 #include "rcutils/error_handling.h"
31 #include "rcutils/format_string.h"
32 #include "rcutils/logging.h"
33 #include "rcutils/logging_macros.h"
34 #include "rcutils/strdup.h"
35 #include "rmw/validate_namespace.h"
36 #include "rmw/validate_node_name.h"
37 
38 #ifdef __cplusplus
39 extern "C"
40 {
41 #endif
42 
44 
53 RCL_LOCAL
55 _rcl_parse_remap_rule(
56  const char * arg,
57  rcl_allocator_t allocator,
58  rcl_remap_t * output_rule);
59 
61 
72 _rcl_parse_param_rule(
73  const char * arg,
74  rcl_params_t * params);
75 
78  const rcl_arguments_t * arguments,
79  rcl_allocator_t allocator,
80  char *** parameter_files)
81 {
82  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
83  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
84  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
85  RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT);
86  *(parameter_files) = allocator.allocate(
87  sizeof(char *) * arguments->impl->num_param_files_args, allocator.state);
88  if (NULL == *parameter_files) {
89  return RCL_RET_BAD_ALLOC;
90  }
91  for (int i = 0; i < arguments->impl->num_param_files_args; ++i) {
92  (*parameter_files)[i] = rcutils_strdup(arguments->impl->parameter_files[i], allocator);
93  if (NULL == (*parameter_files)[i]) {
94  // deallocate allocated memory
95  for (int r = i; r >= 0; --r) {
96  allocator.deallocate((*parameter_files)[r], allocator.state);
97  }
98  allocator.deallocate((*parameter_files), allocator.state);
99  (*parameter_files) = NULL;
100  return RCL_RET_BAD_ALLOC;
101  }
102  }
103  return RCL_RET_OK;
104 }
105 
106 int
108  const rcl_arguments_t * args)
109 {
110  if (NULL == args || NULL == args->impl) {
111  return -1;
112  }
113  return args->impl->num_param_files_args;
114 }
115 
116 rcl_ret_t
118  const rcl_arguments_t * arguments,
119  rcl_params_t ** parameter_overrides)
120 {
121  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
122  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
123  RCL_CHECK_ARGUMENT_FOR_NULL(parameter_overrides, RCL_RET_INVALID_ARGUMENT);
124 
125  if (NULL != *parameter_overrides) {
126  RCL_SET_ERROR_MSG("Output parameter override pointer is not null. May leak memory.");
128  }
129  *parameter_overrides = NULL;
130  if (NULL != arguments->impl->parameter_overrides) {
131  *parameter_overrides = rcl_yaml_node_struct_copy(arguments->impl->parameter_overrides);
132  if (NULL == *parameter_overrides) {
133  return RCL_RET_BAD_ALLOC;
134  }
135  }
136  return RCL_RET_OK;
137 }
138 
139 rcl_ret_t
141  const rcl_arguments_t * arguments,
142  rcl_log_levels_t * log_levels)
143 {
144  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
145  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
146  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
147  const rcl_allocator_t * allocator = &arguments->impl->allocator;
148  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
149 
150  return rcl_log_levels_copy(&arguments->impl->log_levels, log_levels);
151 }
152 
154 
162 RCL_LOCAL
163 rcl_ret_t
164 _rcl_parse_log_level(
165  const char * arg,
166  rcl_log_levels_t * log_levels);
167 
169 
177 RCL_LOCAL
178 rcl_ret_t
179 _rcl_parse_external_log_config_file(
180  const char * arg,
181  rcl_allocator_t allocator,
182  char ** log_config_file);
183 
185 
195 RCL_LOCAL
196 rcl_ret_t
197 _rcl_parse_param_file(
198  const char * arg,
199  rcl_allocator_t allocator,
200  rcl_params_t * params,
201  char ** param_file);
202 
204 
212 RCL_LOCAL
213 rcl_ret_t
214 _rcl_parse_enclave(
215  const char * arg,
216  rcl_allocator_t allocator,
217  char ** enclave);
218 
219 #define RCL_ENABLE_FLAG_PREFIX "--enable-"
220 #define RCL_DISABLE_FLAG_PREFIX "--disable-"
221 
223 
230 RCL_LOCAL
231 rcl_ret_t
232 _rcl_parse_disabling_flag(
233  const char * arg,
234  const char * key,
235  bool * value);
236 
238 
244 rcl_ret_t
245 _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator);
246 
247 rcl_ret_t
249  int argc,
250  const char * const * argv,
251  rcl_allocator_t allocator,
252  rcl_arguments_t * args_output)
253 {
254  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
255  if (argc < 0) {
256  RCL_SET_ERROR_MSG("Argument count cannot be negative");
258  } else if (argc > 0) {
259  RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
260  }
261  RCL_CHECK_ARGUMENT_FOR_NULL(args_output, RCL_RET_INVALID_ARGUMENT);
262 
263  if (args_output->impl != NULL) {
264  RCL_SET_ERROR_MSG("Parse output is not zero-initialized");
266  }
267 
268  rcl_ret_t ret;
269  rcl_ret_t fail_ret;
270 
271  ret = _rcl_allocate_initialized_arguments_impl(args_output, &allocator);
272  if (RCL_RET_OK != ret) {
273  return ret;
274  }
275  rcl_arguments_impl_t * args_impl = args_output->impl;
276 
277  if (argc == 0) {
278  // there are no arguments to parse
279  return RCL_RET_OK;
280  }
281 
282  // over-allocate arrays to match the number of arguments
283  args_impl->remap_rules = allocator.allocate(sizeof(rcl_remap_t) * argc, allocator.state);
284  if (NULL == args_impl->remap_rules) {
285  ret = RCL_RET_BAD_ALLOC;
286  goto fail;
287  }
288 
289  args_impl->parameter_overrides = rcl_yaml_node_struct_init(allocator);
290  if (NULL == args_impl->parameter_overrides) {
291  ret = RCL_RET_BAD_ALLOC;
292  goto fail;
293  }
294 
295  args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state);
296  if (NULL == args_impl->parameter_files) {
297  ret = RCL_RET_BAD_ALLOC;
298  goto fail;
299  }
300  args_impl->unparsed_ros_args = allocator.allocate(sizeof(int) * argc, allocator.state);
301  if (NULL == args_impl->unparsed_ros_args) {
302  ret = RCL_RET_BAD_ALLOC;
303  goto fail;
304  }
305  args_impl->unparsed_args = allocator.allocate(sizeof(int) * argc, allocator.state);
306  if (NULL == args_impl->unparsed_args) {
307  ret = RCL_RET_BAD_ALLOC;
308  goto fail;
309  }
311  ret = rcl_log_levels_init(&log_levels, &allocator, argc);
312  if (ret != RCL_RET_OK) {
313  goto fail;
314  }
315  args_impl->log_levels = log_levels;
316 
317  bool parsing_ros_args = false;
318  for (int i = 0; i < argc; ++i) {
319  if (parsing_ros_args) {
320  // Ignore ROS specific arguments flags
321  if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
322  continue;
323  }
324 
325  // Check for ROS specific arguments explicit end token
326  if (strcmp(RCL_ROS_ARGS_EXPLICIT_END_TOKEN, argv[i]) == 0) {
327  parsing_ros_args = false;
328  continue;
329  }
330 
331  // Attempt to parse argument as parameter override flag
332  if (strcmp(RCL_PARAM_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_PARAM_FLAG, argv[i]) == 0) {
333  if (i + 1 < argc) {
334  // Attempt to parse next argument as parameter override rule
335  if (RCL_RET_OK == _rcl_parse_param_rule(argv[i + 1], args_impl->parameter_overrides)) {
336  RCUTILS_LOG_DEBUG_NAMED(
337  ROS_PACKAGE_NAME, "Got param override rule : %s\n", argv[i + 1]);
338  ++i; // Skip flag here, for loop will skip rule.
339  continue;
340  }
341  rcl_error_string_t prev_error_string = rcl_get_error_string();
342  rcl_reset_error();
343  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
344  "Couldn't parse parameter override rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
345  prev_error_string.str);
346  } else {
347  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
348  "Couldn't parse trailing %s flag. No parameter override rule found.", argv[i]);
349  }
351  goto fail;
352  }
353  RCUTILS_LOG_DEBUG_NAMED(
354  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
355  i, argv[i], RCL_PARAM_FLAG, RCL_SHORT_PARAM_FLAG);
356 
357  // Attempt to parse argument as remap rule flag
358  if (strcmp(RCL_REMAP_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_REMAP_FLAG, argv[i]) == 0) {
359  if (i + 1 < argc) {
360  // Attempt to parse next argument as remap rule
361  rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
363  if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i + 1], allocator, rule)) {
364  ++(args_impl->num_remap_rules);
365  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
366  ++i; // Skip flag here, for loop will skip rule.
367  continue;
368  }
369  rcl_error_string_t prev_error_string = rcl_get_error_string();
370  rcl_reset_error();
371  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
372  "Couldn't parse remap rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
373  prev_error_string.str);
374  } else {
375  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
376  "Couldn't parse trailing %s flag. No remap rule found.", argv[i]);
377  }
379  goto fail;
380  }
381  RCUTILS_LOG_DEBUG_NAMED(
382  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
383  i, argv[i], RCL_REMAP_FLAG, RCL_SHORT_REMAP_FLAG);
384 
385  // Attempt to parse argument as parameter file rule
386  if (strcmp(RCL_PARAM_FILE_FLAG, argv[i]) == 0) {
387  if (i + 1 < argc) {
388  // Attempt to parse next argument as parameter file rule
389  args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
390  if (
391  RCL_RET_OK == _rcl_parse_param_file(
392  argv[i + 1], allocator, args_impl->parameter_overrides,
393  &args_impl->parameter_files[args_impl->num_param_files_args]))
394  {
395  ++(args_impl->num_param_files_args);
396  RCUTILS_LOG_DEBUG_NAMED(
397  ROS_PACKAGE_NAME,
398  "Got params file : %s\ntotal num param files %d",
399  args_impl->parameter_files[args_impl->num_param_files_args - 1],
400  args_impl->num_param_files_args);
401  ++i; // Skip flag here, for loop will skip rule.
402  continue;
403  }
404  rcl_error_string_t prev_error_string = rcl_get_error_string();
405  rcl_reset_error();
406  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
407  "Couldn't parse params file: '%s %s'. Error: %s", argv[i], argv[i + 1],
408  prev_error_string.str);
409  } else {
410  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
411  "Couldn't parse trailing %s flag. No file path provided.", argv[i]);
412  }
414  goto fail;
415  }
416  RCUTILS_LOG_DEBUG_NAMED(
417  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
418  i, argv[i], RCL_PARAM_FILE_FLAG);
419 
420  // Attempt to parse argument as log level configuration
421  if (strcmp(RCL_LOG_LEVEL_FLAG, argv[i]) == 0) {
422  if (i + 1 < argc) {
423  if (RCL_RET_OK ==
424  _rcl_parse_log_level(argv[i + 1], &args_impl->log_levels))
425  {
426  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got log level: %s\n", argv[i + 1]);
427  ++i; // Skip flag here, for loop will skip value.
428  continue;
429  }
430  rcl_error_string_t prev_error_string = rcl_get_error_string();
431  rcl_reset_error();
432  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
433  "Couldn't parse log level: '%s %s'. Error: %s", argv[i], argv[i + 1],
434  prev_error_string.str);
435  } else {
436  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
437  "Couldn't parse trailing log level flag: '%s'. No log level provided.", argv[i]);
438  }
440  goto fail;
441  }
442  RCUTILS_LOG_DEBUG_NAMED(
443  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
444  i, argv[i], RCL_LOG_LEVEL_FLAG);
445 
446  // Attempt to parse argument as log configuration file
447  if (strcmp(RCL_EXTERNAL_LOG_CONFIG_FLAG, argv[i]) == 0) {
448  if (i + 1 < argc) {
449  if (NULL != args_impl->external_log_config_file) {
450  RCUTILS_LOG_DEBUG_NAMED(
451  ROS_PACKAGE_NAME, "Overriding log configuration file : %s\n",
452  args_impl->external_log_config_file);
453  allocator.deallocate(args_impl->external_log_config_file, allocator.state);
454  args_impl->external_log_config_file = NULL;
455  }
456  if (RCL_RET_OK == _rcl_parse_external_log_config_file(
457  argv[i + 1], allocator, &args_impl->external_log_config_file))
458  {
459  RCUTILS_LOG_DEBUG_NAMED(
460  ROS_PACKAGE_NAME, "Got log configuration file : %s\n",
461  args_impl->external_log_config_file);
462  ++i; // Skip flag here, for loop will skip value.
463  continue;
464  }
465  rcl_error_string_t prev_error_string = rcl_get_error_string();
466  rcl_reset_error();
467  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
468  "Couldn't parse log configuration file: '%s %s'. Error: %s", argv[i], argv[i + 1],
469  prev_error_string.str);
470  } else {
471  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
472  "Couldn't parse trailing %s flag. No file path provided.", argv[i]);
473  }
475  goto fail;
476  }
477 
478  // Attempt to parse argument as a security enclave
479  if (strcmp(RCL_ENCLAVE_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_ENCLAVE_FLAG, argv[i]) == 0) {
480  if (i + 1 < argc) {
481  if (NULL != args_impl->enclave) {
482  RCUTILS_LOG_DEBUG_NAMED(
483  ROS_PACKAGE_NAME, "Overriding security enclave : %s\n",
484  args_impl->enclave);
485  allocator.deallocate(args_impl->enclave, allocator.state);
486  args_impl->enclave = NULL;
487  }
488  if (RCL_RET_OK == _rcl_parse_enclave(
489  argv[i + 1], allocator, &args_impl->enclave))
490  {
491  RCUTILS_LOG_DEBUG_NAMED(
492  ROS_PACKAGE_NAME, "Got enclave: %s\n",
493  args_impl->enclave);
494  ++i; // Skip flag here, for loop will skip value.
495  continue;
496  }
497  rcl_error_string_t prev_error_string = rcl_get_error_string();
498  rcl_reset_error();
499  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
500  "Couldn't parse enclave name: '%s %s'. Error: %s", argv[i], argv[i + 1],
501  prev_error_string.str);
502  } else {
503  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
504  "Couldn't parse trailing %s flag. No enclave path provided.", argv[i]);
505  }
507  goto fail;
508  }
509 
510  RCUTILS_LOG_DEBUG_NAMED(
511  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
512  i, argv[i], RCL_EXTERNAL_LOG_CONFIG_FLAG);
513 
514  // Attempt to parse --enable/disable-stdout-logs flag
515  ret = _rcl_parse_disabling_flag(
516  argv[i], RCL_LOG_STDOUT_FLAG_SUFFIX, &args_impl->log_stdout_disabled);
517  if (RCL_RET_OK == ret) {
518  RCUTILS_LOG_DEBUG_NAMED(
519  ROS_PACKAGE_NAME, "Disable log stdout ? %s\n",
520  args_impl->log_stdout_disabled ? "true" : "false");
521  continue;
522  }
523  RCUTILS_LOG_DEBUG_NAMED(
524  ROS_PACKAGE_NAME,
525  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
526  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX,
527  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX, rcl_get_error_string().str);
528  rcl_reset_error();
529 
530  // Attempt to parse --enable/disable-rosout-logs flag
531  ret = _rcl_parse_disabling_flag(
532  argv[i], RCL_LOG_ROSOUT_FLAG_SUFFIX, &args_impl->log_rosout_disabled);
533  if (RCL_RET_OK == ret) {
534  RCUTILS_LOG_DEBUG_NAMED(
535  ROS_PACKAGE_NAME, "Disable log rosout ? %s\n",
536  args_impl->log_rosout_disabled ? "true" : "false");
537  continue;
538  }
539  RCUTILS_LOG_DEBUG_NAMED(
540  ROS_PACKAGE_NAME,
541  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
542  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX,
543  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX, rcl_get_error_string().str);
544  rcl_reset_error();
545 
546  // Attempt to parse --enable/disable-external-lib-logs flag
547  ret = _rcl_parse_disabling_flag(
548  argv[i], RCL_LOG_EXT_LIB_FLAG_SUFFIX, &args_impl->log_ext_lib_disabled);
549  if (RCL_RET_OK == ret) {
550  RCUTILS_LOG_DEBUG_NAMED(
551  ROS_PACKAGE_NAME, "Disable log external lib ? %s\n",
552  args_impl->log_ext_lib_disabled ? "true" : "false");
553  continue;
554  }
555  RCUTILS_LOG_DEBUG_NAMED(
556  ROS_PACKAGE_NAME,
557  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
558  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX,
559  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX, rcl_get_error_string().str);
560  rcl_reset_error();
561 
562  // Argument is an unknown ROS specific argument
563  args_impl->unparsed_ros_args[args_impl->num_unparsed_ros_args] = i;
564  ++(args_impl->num_unparsed_ros_args);
565  } else {
566  // Check for ROS specific arguments flags
567  if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
568  parsing_ros_args = true;
569  continue;
570  }
571 
572  // Attempt to parse argument as remap rule in its deprecated form
573  rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
575  if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) {
576  RCUTILS_LOG_WARN_NAMED(
577  ROS_PACKAGE_NAME,
578  "Found remap rule '%s'. This syntax is deprecated. Use '%s %s %s' instead.",
579  argv[i], RCL_ROS_ARGS_FLAG, RCL_REMAP_FLAG, argv[i]);
580  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
581  ++(args_impl->num_remap_rules);
582  continue;
583  }
584  RCUTILS_LOG_DEBUG_NAMED(
585  ROS_PACKAGE_NAME,
586  "Couldn't parse arg %d (%s) as a remap rule in its deprecated form. Error: %s",
587  i, argv[i], rcl_get_error_string().str);
588  rcl_reset_error();
589 
590  // Argument is not a ROS specific argument
591  args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
592  ++(args_impl->num_unparsed_args);
593  }
594  }
595 
596  // Shrink remap_rules array to match number of successfully parsed rules
597  if (0 == args_impl->num_remap_rules) {
598  // No remap rules
599  allocator.deallocate(args_impl->remap_rules, allocator.state);
600  args_impl->remap_rules = NULL;
601  } else if (args_impl->num_remap_rules < argc) {
602  rcl_remap_t * new_remap_rules = allocator.reallocate(
603  args_impl->remap_rules,
604  sizeof(rcl_remap_t) * args_impl->num_remap_rules,
605  &allocator);
606  if (NULL == new_remap_rules) {
607  ret = RCL_RET_BAD_ALLOC;
608  goto fail;
609  }
610  args_impl->remap_rules = new_remap_rules;
611  }
612 
613  // Shrink Parameter files
614  if (0 == args_impl->num_param_files_args) {
615  allocator.deallocate(args_impl->parameter_files, allocator.state);
616  args_impl->parameter_files = NULL;
617  } else if (args_impl->num_param_files_args < argc) {
618  char ** new_parameter_files = allocator.reallocate(
619  args_impl->parameter_files,
620  sizeof(char *) * args_impl->num_param_files_args,
621  &allocator);
622  if (NULL == new_parameter_files) {
623  ret = RCL_RET_BAD_ALLOC;
624  goto fail;
625  }
626  args_impl->parameter_files = new_parameter_files;
627  }
628 
629  // Drop parameter overrides if none was found.
630  if (0U == args_impl->parameter_overrides->num_nodes) {
631  rcl_yaml_node_struct_fini(args_impl->parameter_overrides);
632  args_impl->parameter_overrides = NULL;
633  }
634 
635  // Shrink unparsed_ros_args
636  if (0 == args_impl->num_unparsed_ros_args) {
637  // No unparsed ros args
638  allocator.deallocate(args_impl->unparsed_ros_args, allocator.state);
639  args_impl->unparsed_ros_args = NULL;
640  } else if (args_impl->num_unparsed_ros_args < argc) {
641  args_impl->unparsed_ros_args = rcutils_reallocf(
642  args_impl->unparsed_ros_args, sizeof(int) * args_impl->num_unparsed_ros_args, &allocator);
643  if (NULL == args_impl->unparsed_ros_args) {
644  ret = RCL_RET_BAD_ALLOC;
645  goto fail;
646  }
647  }
648 
649  // Shrink unparsed_args
650  if (0 == args_impl->num_unparsed_args) {
651  // No unparsed args
652  allocator.deallocate(args_impl->unparsed_args, allocator.state);
653  args_impl->unparsed_args = NULL;
654  } else if (args_impl->num_unparsed_args < argc) {
655  args_impl->unparsed_args = rcutils_reallocf(
656  args_impl->unparsed_args, sizeof(int) * args_impl->num_unparsed_args, &allocator);
657  if (NULL == args_impl->unparsed_args) {
658  ret = RCL_RET_BAD_ALLOC;
659  goto fail;
660  }
661  }
662 
663  // Shrink logger settings of log levels
664  ret = rcl_log_levels_shrink_to_size(&args_impl->log_levels);
665  if (ret != RCL_RET_OK) {
666  goto fail;
667  }
668 
669  return RCL_RET_OK;
670 fail:
671  fail_ret = ret;
672  if (NULL != args_impl) {
673  ret = rcl_arguments_fini(args_output);
674  if (RCL_RET_OK != ret) {
675  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini arguments after earlier failure");
676  }
677  }
678  return fail_ret;
679 }
680 
681 int
683  const rcl_arguments_t * args)
684 {
685  if (NULL == args || NULL == args->impl) {
686  return -1;
687  }
688  return args->impl->num_unparsed_args;
689 }
690 
691 rcl_ret_t
693  const rcl_arguments_t * args,
694  rcl_allocator_t allocator,
695  int ** output_unparsed_indices)
696 {
697  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
698  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
699  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
700  RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_indices, RCL_RET_INVALID_ARGUMENT);
701 
702  *output_unparsed_indices = NULL;
703  if (args->impl->num_unparsed_args) {
704  *output_unparsed_indices = allocator.allocate(
705  sizeof(int) * args->impl->num_unparsed_args, allocator.state);
706  if (NULL == *output_unparsed_indices) {
707  return RCL_RET_BAD_ALLOC;
708  }
709  for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
710  (*output_unparsed_indices)[i] = args->impl->unparsed_args[i];
711  }
712  }
713  return RCL_RET_OK;
714 }
715 
716 int
718  const rcl_arguments_t * args)
719 {
720  if (NULL == args || NULL == args->impl) {
721  return -1;
722  }
723  return args->impl->num_unparsed_ros_args;
724 }
725 
726 rcl_ret_t
728  const rcl_arguments_t * args,
729  rcl_allocator_t allocator,
730  int ** output_unparsed_ros_indices)
731 {
732  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
733  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
734  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
735  RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_ros_indices, RCL_RET_INVALID_ARGUMENT);
736 
737  *output_unparsed_ros_indices = NULL;
738  if (args->impl->num_unparsed_ros_args) {
739  *output_unparsed_ros_indices = allocator.allocate(
740  sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
741  if (NULL == *output_unparsed_ros_indices) {
742  return RCL_RET_BAD_ALLOC;
743  }
744  for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
745  (*output_unparsed_ros_indices)[i] = args->impl->unparsed_ros_args[i];
746  }
747  }
748  return RCL_RET_OK;
749 }
750 
753 {
754  static rcl_arguments_t default_arguments = {
755  .impl = NULL
756  };
757  return default_arguments;
758 }
759 
760 rcl_ret_t
762  const char * const * argv,
763  const rcl_arguments_t * args,
764  rcl_allocator_t allocator,
765  int * nonros_argc,
766  const char *** nonros_argv)
767 {
768  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
769  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
770  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT);
771  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argv, RCL_RET_INVALID_ARGUMENT);
772  if (NULL != *nonros_argv) {
773  RCL_SET_ERROR_MSG("Output nonros_argv pointer is not null. May leak memory.");
775  }
776 
777  *nonros_argc = rcl_arguments_get_count_unparsed(args);
778  if (*nonros_argc < 0) {
779  RCL_SET_ERROR_MSG("Failed to get unparsed non ROS specific arguments count.");
781  } else if (*nonros_argc > 0) {
782  RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
783  }
784 
785  *nonros_argv = NULL;
786  if (0 == *nonros_argc) {
787  return RCL_RET_OK;
788  }
789 
790  int * unparsed_indices = NULL;
791  rcl_ret_t ret = rcl_arguments_get_unparsed(args, allocator, &unparsed_indices);
792 
793  if (RCL_RET_OK != ret) {
794  return ret;
795  }
796 
797  size_t alloc_size = sizeof(char *) * *nonros_argc;
798  *nonros_argv = allocator.allocate(alloc_size, allocator.state);
799  if (NULL == *nonros_argv) {
800  allocator.deallocate(unparsed_indices, allocator.state);
801  return RCL_RET_BAD_ALLOC;
802  }
803  for (int i = 0; i < *nonros_argc; ++i) {
804  (*nonros_argv)[i] = argv[unparsed_indices[i]];
805  }
806 
807  allocator.deallocate(unparsed_indices, allocator.state);
808  return RCL_RET_OK;
809 }
810 
811 rcl_ret_t
813  const rcl_arguments_t * args,
814  rcl_arguments_t * args_out)
815 {
816  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
817  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
818 
819  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
820  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
821  RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
822  if (NULL != args_out->impl) {
823  RCL_SET_ERROR_MSG("args_out must be zero initialized");
825  }
826 
827  rcl_allocator_t allocator = args->impl->allocator;
828 
829  rcl_ret_t ret = _rcl_allocate_initialized_arguments_impl(args_out, &allocator);
830  if (RCL_RET_OK != ret) {
831  return ret;
832  }
833 
834  if (args->impl->num_unparsed_args) {
835  // Copy unparsed args
836  args_out->impl->unparsed_args = allocator.allocate(
837  sizeof(int) * args->impl->num_unparsed_args, allocator.state);
838  if (NULL == args_out->impl->unparsed_args) {
839  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
840  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
841  }
842  return RCL_RET_BAD_ALLOC;
843  }
844  for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
845  args_out->impl->unparsed_args[i] = args->impl->unparsed_args[i];
846  }
847  args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
848  }
849 
850  if (args->impl->num_unparsed_ros_args) {
851  // Copy unparsed ROS args
852  args_out->impl->unparsed_ros_args = allocator.allocate(
853  sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
854  if (NULL == args_out->impl->unparsed_ros_args) {
855  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
856  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
857  }
858  return RCL_RET_BAD_ALLOC;
859  }
860  for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
861  args_out->impl->unparsed_ros_args[i] = args->impl->unparsed_ros_args[i];
862  }
864  }
865 
866  if (args->impl->num_remap_rules) {
867  // Copy remap rules
868  args_out->impl->remap_rules = allocator.allocate(
869  sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state);
870  if (NULL == args_out->impl->remap_rules) {
871  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
872  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
873  }
874  return RCL_RET_BAD_ALLOC;
875  }
876  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
878  ret = rcl_remap_copy(
879  &(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i]));
880  if (RCL_RET_OK != ret) {
881  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
882  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
883  }
884  return ret;
885  }
886  ++(args_out->impl->num_remap_rules);
887  }
888  }
889 
890  // Copy parameter rules
891  if (args->impl->parameter_overrides) {
892  args_out->impl->parameter_overrides =
893  rcl_yaml_node_struct_copy(args->impl->parameter_overrides);
894  }
895 
896  // Copy parameter files
897  if (args->impl->num_param_files_args) {
898  args_out->impl->parameter_files = allocator.zero_allocate(
899  args->impl->num_param_files_args, sizeof(char *), allocator.state);
900  if (NULL == args_out->impl->parameter_files) {
901  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
902  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
903  }
904  return RCL_RET_BAD_ALLOC;
905  }
906  for (int i = 0; i < args->impl->num_param_files_args; ++i) {
907  args_out->impl->parameter_files[i] =
908  rcutils_strdup(args->impl->parameter_files[i], allocator);
909  if (NULL == args_out->impl->parameter_files[i]) {
910  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
911  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
912  }
913  return RCL_RET_BAD_ALLOC;
914  }
915  ++(args_out->impl->num_param_files_args);
916  }
917  }
918  char * enclave_copy = rcutils_strdup(args->impl->enclave, allocator);
919  if (args->impl->enclave && !enclave_copy) {
920  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
921  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
922  } else {
923  RCL_SET_ERROR_MSG("Error while copying enclave argument");
924  }
925  return RCL_RET_BAD_ALLOC;
926  }
927  args_out->impl->enclave = enclave_copy;
928  return RCL_RET_OK;
929 }
930 
931 rcl_ret_t
933  rcl_arguments_t * args)
934 {
935  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
936  if (args->impl) {
937  rcl_ret_t ret = RCL_RET_OK;
938  if (args->impl->remap_rules) {
939  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
940  rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i]));
941  if (remap_ret != RCL_RET_OK) {
942  ret = remap_ret;
943  RCUTILS_LOG_ERROR_NAMED(
944  ROS_PACKAGE_NAME,
945  "Failed to finalize remap rule while finalizing arguments. Continuing...");
946  }
947  }
948  args->impl->allocator.deallocate(args->impl->remap_rules, args->impl->allocator.state);
949  args->impl->remap_rules = NULL;
950  args->impl->num_remap_rules = 0;
951  }
952 
953  rcl_ret_t log_levels_ret = rcl_log_levels_fini(&args->impl->log_levels);
954  if (log_levels_ret != RCL_RET_OK) {
955  ret = log_levels_ret;
956  RCUTILS_LOG_ERROR_NAMED(
957  ROS_PACKAGE_NAME,
958  "Failed to finalize log levels while finalizing arguments. Continuing...");
959  }
960 
961  args->impl->allocator.deallocate(args->impl->unparsed_args, args->impl->allocator.state);
962  args->impl->num_unparsed_args = 0;
963  args->impl->unparsed_args = NULL;
964 
965  args->impl->allocator.deallocate(args->impl->unparsed_ros_args, args->impl->allocator.state);
966  args->impl->num_unparsed_ros_args = 0;
967  args->impl->unparsed_ros_args = NULL;
968 
969  if (args->impl->parameter_overrides) {
970  rcl_yaml_node_struct_fini(args->impl->parameter_overrides);
971  args->impl->parameter_overrides = NULL;
972  }
973 
974  if (args->impl->parameter_files) {
975  for (int p = 0; p < args->impl->num_param_files_args; ++p) {
976  args->impl->allocator.deallocate(
977  args->impl->parameter_files[p], args->impl->allocator.state);
978  }
979  args->impl->allocator.deallocate(args->impl->parameter_files, args->impl->allocator.state);
980  args->impl->num_param_files_args = 0;
981  args->impl->parameter_files = NULL;
982  }
983  args->impl->allocator.deallocate(args->impl->enclave, args->impl->allocator.state);
984 
985  if (NULL != args->impl->external_log_config_file) {
986  args->impl->allocator.deallocate(
987  args->impl->external_log_config_file, args->impl->allocator.state);
988  args->impl->external_log_config_file = NULL;
989  }
990 
991  args->impl->allocator.deallocate(args->impl, args->impl->allocator.state);
992  args->impl = NULL;
993  return ret;
994  }
995  RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice");
996  return RCL_RET_ERROR;
997 }
998 
1000 
1003 RCL_LOCAL
1004 rcl_ret_t
1005 _rcl_parse_remap_fully_qualified_namespace(
1006  rcl_lexer_lookahead2_t * lex_lookahead)
1007 {
1008  rcl_ret_t ret;
1009 
1010  // Check arguments sanity
1011  assert(NULL != lex_lookahead);
1012 
1013  // Must have at least one Forward slash /
1014  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1015  if (RCL_RET_WRONG_LEXEME == ret) {
1017  }
1018 
1019  // repeated tokens and slashes (allow trailing slash, but don't require it)
1020  while (true) {
1021  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, NULL, NULL);
1022  if (RCL_RET_WRONG_LEXEME == ret) {
1023  rcl_reset_error();
1024  break;
1025  }
1026  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1027  if (RCL_RET_WRONG_LEXEME == ret) {
1028  rcl_reset_error();
1029  break;
1030  }
1031  }
1032  return RCL_RET_OK;
1033 }
1034 
1036 
1039 RCL_LOCAL
1040 rcl_ret_t
1041 _rcl_parse_remap_replacement_token(rcl_lexer_lookahead2_t * lex_lookahead)
1042 {
1043  rcl_ret_t ret;
1044  rcl_lexeme_t lexeme;
1045 
1046  // Check arguments sanity
1047  assert(NULL != lex_lookahead);
1048 
1049  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1050  if (RCL_RET_OK != ret) {
1051  return ret;
1052  }
1053 
1054  if (
1055  RCL_LEXEME_BR1 == lexeme || RCL_LEXEME_BR2 == lexeme || RCL_LEXEME_BR3 == lexeme ||
1056  RCL_LEXEME_BR4 == lexeme || RCL_LEXEME_BR5 == lexeme || RCL_LEXEME_BR6 == lexeme ||
1057  RCL_LEXEME_BR7 == lexeme || RCL_LEXEME_BR8 == lexeme || RCL_LEXEME_BR9 == lexeme)
1058  {
1059  RCL_SET_ERROR_MSG("Backreferences are not implemented");
1060  return RCL_RET_ERROR;
1061  } else if (RCL_LEXEME_TOKEN == lexeme) {
1062  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1063  } else {
1065  }
1066 
1067  return ret;
1068 }
1069 
1071 
1074 RCL_LOCAL
1075 rcl_ret_t
1076 _rcl_parse_remap_replacement_name(
1077  rcl_lexer_lookahead2_t * lex_lookahead,
1078  rcl_remap_t * rule)
1079 {
1080  rcl_ret_t ret;
1081  rcl_lexeme_t lexeme;
1082 
1083  // Check arguments sanity
1084  assert(NULL != lex_lookahead);
1085  assert(NULL != rule);
1086 
1087  const char * replacement_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1088  if (NULL == replacement_start) {
1089  RCL_SET_ERROR_MSG("failed to get start of replacement");
1090  return RCL_RET_ERROR;
1091  }
1092 
1093  // private name (~/...) or fully qualified name (/...) ?
1094  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1095  if (RCL_RET_OK != ret) {
1096  return ret;
1097  }
1098  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1099  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1100  }
1101  if (RCL_RET_OK != ret) {
1102  return ret;
1103  }
1104 
1105  // token ( '/' token )*
1106  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1107  if (RCL_RET_OK != ret) {
1108  return ret;
1109  }
1110  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1111  if (RCL_RET_OK != ret) {
1112  return ret;
1113  }
1114  while (RCL_LEXEME_EOF != lexeme) {
1115  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1116  if (RCL_RET_WRONG_LEXEME == ret) {
1118  }
1119  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1120  if (RCL_RET_OK != ret) {
1121  return ret;
1122  }
1123  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1124  if (RCL_RET_OK != ret) {
1125  return ret;
1126  }
1127  }
1128 
1129  // Copy replacement into rule
1130  const char * replacement_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1131  size_t length = (size_t)(replacement_end - replacement_start);
1132  rule->impl->replacement = rcutils_strndup(
1133  replacement_start, length, rule->impl->allocator);
1134  if (NULL == rule->impl->replacement) {
1135  RCL_SET_ERROR_MSG("failed to copy replacement");
1136  return RCL_RET_BAD_ALLOC;
1137  }
1138 
1139  return RCL_RET_OK;
1140 }
1141 
1143 
1146 RCL_LOCAL
1147 rcl_ret_t
1148 _rcl_parse_resource_match_token(rcl_lexer_lookahead2_t * lex_lookahead)
1149 {
1150  rcl_ret_t ret;
1151  rcl_lexeme_t lexeme;
1152 
1153  // Check arguments sanity
1154  assert(NULL != lex_lookahead);
1155 
1156  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1157  if (RCL_RET_OK != ret) {
1158  return ret;
1159  }
1160 
1161  if (RCL_LEXEME_TOKEN == lexeme) {
1162  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1163  } else if (RCL_LEXEME_WILD_ONE == lexeme) {
1164  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1165  return RCL_RET_ERROR;
1166  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1167  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1168  return RCL_RET_ERROR;
1169  } else {
1170  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1171  ret = RCL_RET_WRONG_LEXEME;
1172  }
1173 
1174  return ret;
1175 }
1176 
1178 
1181 RCL_LOCAL
1182 rcl_ret_t
1183 _rcl_parse_resource_match(
1184  rcl_lexer_lookahead2_t * lex_lookahead,
1185  rcl_allocator_t allocator,
1186  char ** resource_match)
1187 {
1188  rcl_ret_t ret;
1189  rcl_lexeme_t lexeme;
1190 
1191  // Check arguments sanity
1192  assert(NULL != lex_lookahead);
1193  assert(rcutils_allocator_is_valid(&allocator));
1194  assert(NULL != resource_match);
1195  assert(NULL == *resource_match);
1196 
1197  const char * match_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1198  if (NULL == match_start) {
1199  RCL_SET_ERROR_MSG("failed to get start of match");
1200  return RCL_RET_ERROR;
1201  }
1202 
1203  // private name (~/...) or fully qualified name (/...) ?
1204  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1205  if (RCL_RET_OK != ret) {
1206  return ret;
1207  }
1208  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1209  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1210  if (RCL_RET_OK != ret) {
1211  return ret;
1212  }
1213  }
1214 
1215  // token ( '/' token )*
1216  ret = _rcl_parse_resource_match_token(lex_lookahead);
1217  if (RCL_RET_OK != ret) {
1218  return ret;
1219  }
1220  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1221  if (RCL_RET_OK != ret) {
1222  return ret;
1223  }
1224  while (RCL_LEXEME_SEPARATOR != lexeme) {
1225  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1226  if (RCL_RET_WRONG_LEXEME == ret) {
1228  }
1229  ret = _rcl_parse_resource_match_token(lex_lookahead);
1230  if (RCL_RET_OK != ret) {
1231  return ret;
1232  }
1233  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1234  if (RCL_RET_OK != ret) {
1235  return ret;
1236  }
1237  }
1238 
1239  // Copy match into rule
1240  const char * match_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1241  const size_t length = (size_t)(match_end - match_start);
1242  *resource_match = rcutils_strndup(match_start, length, allocator);
1243  if (NULL == *resource_match) {
1244  RCL_SET_ERROR_MSG("failed to copy match");
1245  return RCL_RET_BAD_ALLOC;
1246  }
1247 
1248  return RCL_RET_OK;
1249 }
1250 
1251 RCL_LOCAL
1252 rcl_ret_t
1253 _rcl_parse_param_name_token(rcl_lexer_lookahead2_t * lex_lookahead)
1254 {
1255  rcl_ret_t ret;
1256  rcl_lexeme_t lexeme;
1257 
1258  // Check arguments sanity
1259  assert(NULL != lex_lookahead);
1260 
1261  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1262  if (RCL_RET_OK != ret) {
1263  return ret;
1264  }
1265  if (RCL_LEXEME_TOKEN != lexeme && RCL_LEXEME_FORWARD_SLASH != lexeme) {
1266  if (RCL_LEXEME_WILD_ONE == lexeme) {
1267  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1268  return RCL_RET_ERROR;
1269  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1270  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1271  return RCL_RET_ERROR;
1272  } else {
1273  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1274  return RCL_RET_WRONG_LEXEME;
1275  }
1276  }
1277  do {
1278  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1279  if (RCL_RET_OK != ret) {
1280  return ret;
1281  }
1282  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1283  if (RCL_RET_OK != ret) {
1284  return ret;
1285  }
1286  } while (RCL_LEXEME_TOKEN == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme);
1287  return RCL_RET_OK;
1288 }
1289 
1291 
1294 // TODO(hidmic): remove when parameter names are standardized to use slashes
1295 // in lieu of dots.
1296 RCL_LOCAL
1297 rcl_ret_t
1298 _rcl_parse_param_name(
1299  rcl_lexer_lookahead2_t * lex_lookahead,
1300  rcl_allocator_t allocator,
1301  char ** param_name)
1302 {
1303  rcl_ret_t ret;
1304  rcl_lexeme_t lexeme;
1305 
1306  // Check arguments sanity
1307  assert(NULL != lex_lookahead);
1308  assert(rcutils_allocator_is_valid(&allocator));
1309  assert(NULL != param_name);
1310  assert(NULL == *param_name);
1311 
1312  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1313  if (NULL == name_start) {
1314  RCL_SET_ERROR_MSG("failed to get start of param name");
1315  return RCL_RET_ERROR;
1316  }
1317 
1318  // token ( '.' token )*
1319  ret = _rcl_parse_param_name_token(lex_lookahead);
1320  if (RCL_RET_OK != ret) {
1321  return ret;
1322  }
1323  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1324  if (RCL_RET_OK != ret) {
1325  return ret;
1326  }
1327  while (RCL_LEXEME_SEPARATOR != lexeme) {
1328  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_DOT, NULL, NULL);
1329  if (RCL_RET_WRONG_LEXEME == ret) {
1331  }
1332  ret = _rcl_parse_param_name_token(lex_lookahead);
1333  if (RCL_RET_OK != ret) {
1334  return ret;
1335  }
1336  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1337  if (RCL_RET_OK != ret) {
1338  return ret;
1339  }
1340  }
1341 
1342  // Copy param name
1343  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1344  const size_t length = (size_t)(name_end - name_start);
1345  *param_name = rcutils_strndup(name_start, length, allocator);
1346  if (NULL == *param_name) {
1347  RCL_SET_ERROR_MSG("failed to copy param name");
1348  return RCL_RET_BAD_ALLOC;
1349  }
1350 
1351  return RCL_RET_OK;
1352 }
1353 
1354 
1356 
1359 RCL_LOCAL
1360 rcl_ret_t
1361 _rcl_parse_remap_match_name(
1362  rcl_lexer_lookahead2_t * lex_lookahead,
1363  rcl_remap_t * rule)
1364 {
1365  rcl_ret_t ret;
1366  rcl_lexeme_t lexeme;
1367 
1368  // Check arguments sanity
1369  assert(NULL != lex_lookahead);
1370  assert(NULL != rule);
1371 
1372  // rostopic:// rosservice://
1373  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1374  if (RCL_RET_OK != ret) {
1375  return ret;
1376  }
1377  if (RCL_LEXEME_URL_SERVICE == lexeme) {
1378  rule->impl->type = RCL_SERVICE_REMAP;
1379  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1380  } else if (RCL_LEXEME_URL_TOPIC == lexeme) {
1381  rule->impl->type = RCL_TOPIC_REMAP;
1382  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1383  } else {
1384  rule->impl->type = (RCL_TOPIC_REMAP | RCL_SERVICE_REMAP);
1385  }
1386  if (RCL_RET_OK != ret) {
1387  return ret;
1388  }
1389 
1390  ret = _rcl_parse_resource_match(
1391  lex_lookahead, rule->impl->allocator, &rule->impl->match);
1392  if (RCL_RET_WRONG_LEXEME == ret) {
1394  }
1395  return ret;
1396 }
1397 
1399 
1402 RCL_LOCAL
1403 rcl_ret_t
1404 _rcl_parse_remap_name_remap(
1405  rcl_lexer_lookahead2_t * lex_lookahead,
1406  rcl_remap_t * rule)
1407 {
1408  rcl_ret_t ret;
1409 
1410  // Check arguments sanity
1411  assert(NULL != lex_lookahead);
1412  assert(NULL != rule);
1413 
1414  // match
1415  ret = _rcl_parse_remap_match_name(lex_lookahead, rule);
1416  if (RCL_RET_OK != ret) {
1417  return ret;
1418  }
1419  // :=
1420  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1421  if (RCL_RET_WRONG_LEXEME == ret) {
1423  }
1424  // replacement
1425  ret = _rcl_parse_remap_replacement_name(lex_lookahead, rule);
1426  if (RCL_RET_OK != ret) {
1427  return ret;
1428  }
1429 
1430  return RCL_RET_OK;
1431 }
1432 
1434 
1437 RCL_LOCAL
1438 rcl_ret_t
1439 _rcl_parse_remap_namespace_replacement(
1440  rcl_lexer_lookahead2_t * lex_lookahead,
1441  rcl_remap_t * rule)
1442 {
1443  rcl_ret_t ret;
1444 
1445  // Check arguments sanity
1446  assert(NULL != lex_lookahead);
1447  assert(NULL != rule);
1448 
1449  // __ns
1450  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NS, NULL, NULL);
1451  if (RCL_RET_WRONG_LEXEME == ret) {
1453  }
1454  // :=
1455  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1456  if (RCL_RET_WRONG_LEXEME == ret) {
1458  }
1459  // /foo/bar
1460  const char * ns_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1461  if (NULL == ns_start) {
1462  RCL_SET_ERROR_MSG("failed to get start of namespace");
1463  return RCL_RET_ERROR;
1464  }
1465  ret = _rcl_parse_remap_fully_qualified_namespace(lex_lookahead);
1466  if (RCL_RET_OK != ret) {
1467  if (RCL_RET_INVALID_REMAP_RULE == ret) {
1468  // The name didn't start with a leading forward slash
1469  RCUTILS_LOG_WARN_NAMED(
1470  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1471  }
1472  return ret;
1473  }
1474  // There should be nothing left
1475  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1476  if (RCL_RET_OK != ret) {
1477  // The name must have started with a leading forward slash but had an otherwise invalid format
1478  RCUTILS_LOG_WARN_NAMED(
1479  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1480  return ret;
1481  }
1482 
1483  // Copy namespace into rule
1484  const char * ns_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1485  size_t length = (size_t)(ns_end - ns_start);
1486  rule->impl->replacement = rcutils_strndup(ns_start, length, rule->impl->allocator);
1487  if (NULL == rule->impl->replacement) {
1488  RCL_SET_ERROR_MSG("failed to copy namespace");
1489  return RCL_RET_BAD_ALLOC;
1490  }
1491 
1492  rule->impl->type = RCL_NAMESPACE_REMAP;
1493  return RCL_RET_OK;
1494 }
1495 
1497 
1500 RCL_LOCAL
1501 rcl_ret_t
1502 _rcl_parse_remap_nodename_replacement(
1503  rcl_lexer_lookahead2_t * lex_lookahead,
1504  rcl_remap_t * rule)
1505 {
1506  rcl_ret_t ret;
1507  const char * node_name;
1508  size_t length;
1509 
1510  // Check arguments sanity
1511  assert(NULL != lex_lookahead);
1512  assert(NULL != rule);
1513 
1514  // __node
1515  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NODE, NULL, NULL);
1516  if (RCL_RET_WRONG_LEXEME == ret) {
1518  }
1519  // :=
1520  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1521  if (RCL_RET_WRONG_LEXEME == ret) {
1523  }
1524  // new_node_name
1525  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &node_name, &length);
1526  if (RCL_RET_WRONG_LEXEME == ret) {
1527  node_name = rcl_lexer_lookahead2_get_text(lex_lookahead);
1528  RCUTILS_LOG_WARN_NAMED(
1529  ROS_PACKAGE_NAME, "Node name not remapped to invalid name: '%s'", node_name);
1531  }
1532  if (RCL_RET_OK != ret) {
1533  return ret;
1534  }
1535  // copy the node name into the replacement side of the rule
1536  rule->impl->replacement = rcutils_strndup(node_name, length, rule->impl->allocator);
1537  if (NULL == rule->impl->replacement) {
1538  RCL_SET_ERROR_MSG("failed to allocate node name");
1539  return RCL_RET_BAD_ALLOC;
1540  }
1541 
1542  rule->impl->type = RCL_NODENAME_REMAP;
1543  return RCL_RET_OK;
1544 }
1545 
1547 RCL_LOCAL
1548 rcl_ret_t
1549 _rcl_parse_nodename_prefix(
1550  rcl_lexer_lookahead2_t * lex_lookahead,
1551  rcl_allocator_t allocator,
1552  char ** node_name)
1553 {
1554  size_t length = 0;
1555  const char * token = NULL;
1556 
1557  // Check arguments sanity
1558  assert(NULL != lex_lookahead);
1559  assert(rcutils_allocator_is_valid(&allocator));
1560  assert(NULL != node_name);
1561  assert(NULL == *node_name);
1562 
1563  // Expect a token and a colon
1564  rcl_ret_t ret =
1565  rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &token, &length);
1566  if (RCL_RET_OK != ret) {
1567  return ret;
1568  }
1569  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_COLON, NULL, NULL);
1570  if (RCL_RET_OK != ret) {
1571  return ret;
1572  }
1573 
1574  // Copy the node name
1575  *node_name = rcutils_strndup(token, length, allocator);
1576  if (NULL == *node_name) {
1577  RCL_SET_ERROR_MSG("failed to allocate node name");
1578  return RCL_RET_BAD_ALLOC;
1579  }
1580 
1581  return RCL_RET_OK;
1582 }
1583 
1585 
1589 RCL_LOCAL
1590 rcl_ret_t
1591 _rcl_parse_remap_nodename_prefix(
1592  rcl_lexer_lookahead2_t * lex_lookahead,
1593  rcl_remap_t * rule)
1594 {
1595  // Check arguments sanity
1596  assert(NULL != lex_lookahead);
1597  assert(NULL != rule);
1598 
1599  rcl_ret_t ret = _rcl_parse_nodename_prefix(
1600  lex_lookahead, rule->impl->allocator, &rule->impl->node_name);
1601  if (RCL_RET_WRONG_LEXEME == ret) {
1603  }
1604  return ret;
1605 }
1606 
1608 
1616 RCL_LOCAL
1617 rcl_ret_t
1618 _rcl_parse_remap_begin_remap_rule(
1619  rcl_lexer_lookahead2_t * lex_lookahead,
1620  rcl_remap_t * rule)
1621 {
1622  rcl_ret_t ret;
1623  rcl_lexeme_t lexeme1;
1624  rcl_lexeme_t lexeme2;
1625 
1626  // Check arguments sanity
1627  assert(NULL != lex_lookahead);
1628  assert(NULL != rule);
1629 
1630  // Check for optional nodename prefix
1631  ret = rcl_lexer_lookahead2_peek2(lex_lookahead, &lexeme1, &lexeme2);
1632  if (RCL_RET_OK != ret) {
1633  return ret;
1634  }
1635  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1636  ret = _rcl_parse_remap_nodename_prefix(lex_lookahead, rule);
1637  if (RCL_RET_OK != ret) {
1638  return ret;
1639  }
1640  }
1641 
1642  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme1);
1643  if (RCL_RET_OK != ret) {
1644  return ret;
1645  }
1646 
1647  // What type of rule is this (node name replacement, namespace replacement, or name remap)?
1648  if (RCL_LEXEME_NODE == lexeme1) {
1649  ret = _rcl_parse_remap_nodename_replacement(lex_lookahead, rule);
1650  if (RCL_RET_OK != ret) {
1651  return ret;
1652  }
1653  } else if (RCL_LEXEME_NS == lexeme1) {
1654  ret = _rcl_parse_remap_namespace_replacement(lex_lookahead, rule);
1655  if (RCL_RET_OK != ret) {
1656  return ret;
1657  }
1658  } else {
1659  ret = _rcl_parse_remap_name_remap(lex_lookahead, rule);
1660  if (RCL_RET_OK != ret) {
1661  return ret;
1662  }
1663  }
1664 
1665  // Make sure all characters in string have been consumed
1666  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1667  if (RCL_RET_WRONG_LEXEME == ret) {
1669  }
1670  return ret;
1671 }
1672 
1673 RCL_LOCAL
1674 rcl_ret_t
1675 _rcl_parse_log_level_name(
1676  rcl_lexer_lookahead2_t * lex_lookahead,
1677  rcl_allocator_t * allocator,
1678  char ** logger_name)
1679 {
1680  rcl_lexeme_t lexeme;
1681 
1682  // Check arguments sanity
1683  assert(NULL != lex_lookahead);
1684  assert(rcutils_allocator_is_valid(allocator));
1685  assert(NULL != logger_name);
1686  assert(NULL == *logger_name);
1687 
1688  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1689  if (NULL == name_start) {
1690  RCL_SET_ERROR_MSG("failed to get start of logger name");
1691  return RCL_RET_ERROR;
1692  }
1693 
1694  rcl_ret_t ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1695  if (RCL_RET_OK != ret) {
1696  return ret;
1697  }
1698 
1699  while (RCL_LEXEME_SEPARATOR != lexeme) {
1700  ret = rcl_lexer_lookahead2_expect(lex_lookahead, lexeme, NULL, NULL);
1701  if (RCL_RET_OK != ret) {
1702  return ret;
1703  }
1704 
1705  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1706  if (RCL_RET_OK != ret) {
1707  return ret;
1708  }
1709 
1710  if (lexeme == RCL_LEXEME_EOF) {
1712  return ret;
1713  }
1714  }
1715 
1716  // Copy logger name
1717  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1718  const size_t length = (size_t)(name_end - name_start);
1719  *logger_name = rcutils_strndup(name_start, length, *allocator);
1720  if (NULL == *logger_name) {
1721  RCL_SET_ERROR_MSG("failed to copy logger name");
1722  return RCL_RET_BAD_ALLOC;
1723  }
1724 
1725  return RCL_RET_OK;
1726 }
1727 
1728 rcl_ret_t
1729 _rcl_parse_log_level(
1730  const char * arg,
1731  rcl_log_levels_t * log_levels)
1732 {
1733  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1734  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
1735  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels->logger_settings, RCL_RET_INVALID_ARGUMENT);
1736  rcl_allocator_t * allocator = &log_levels->allocator;
1737  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
1738 
1739  rcl_ret_t ret = RCL_RET_OK;
1740  char * logger_name = NULL;
1741  int level = 0;
1742  rcutils_ret_t rcutils_ret = RCUTILS_RET_OK;
1743 
1745 
1746  ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, *allocator);
1747  if (RCL_RET_OK != ret) {
1748  return ret;
1749  }
1750 
1751  ret = _rcl_parse_log_level_name(&lex_lookahead, allocator, &logger_name);
1752  if (RCL_RET_OK == ret) {
1753  if (strlen(logger_name) == 0) {
1754  RCL_SET_ERROR_MSG("Argument has an invalid logger item that name is empty");
1756  goto cleanup;
1757  }
1758 
1759  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1760  if (RCL_RET_WRONG_LEXEME == ret) {
1762  goto cleanup;
1763  }
1764 
1765  const char * level_token;
1766  size_t level_token_length;
1768  &lex_lookahead, RCL_LEXEME_TOKEN, &level_token, &level_token_length);
1769  if (RCL_RET_WRONG_LEXEME == ret) {
1771  goto cleanup;
1772  }
1773 
1774  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1775  if (RCL_RET_OK != ret) {
1777  goto cleanup;
1778  }
1779 
1780  rcutils_ret = rcutils_logging_severity_level_from_string(
1781  level_token, *allocator, &level);
1782  if (RCUTILS_RET_OK == rcutils_ret) {
1784  log_levels, logger_name, (rcl_log_severity_t)level);
1785  if (ret != RCL_RET_OK) {
1786  goto cleanup;
1787  }
1788  }
1789  } else {
1790  rcutils_ret = rcutils_logging_severity_level_from_string(
1791  arg, *allocator, &level);
1792  if (RCUTILS_RET_OK == rcutils_ret) {
1793  if (log_levels->default_logger_level != (rcl_log_severity_t)level) {
1794  if (log_levels->default_logger_level != RCUTILS_LOG_SEVERITY_UNSET) {
1795  RCUTILS_LOG_DEBUG_NAMED(
1796  ROS_PACKAGE_NAME, "Minimum default log level will be replaced from %d to %d",
1797  log_levels->default_logger_level, level);
1798  }
1799  log_levels->default_logger_level = (rcl_log_severity_t)level;
1800  }
1801  ret = RCL_RET_OK;
1802  }
1803  }
1804 
1805  if (RCUTILS_RET_OK != rcutils_ret) {
1806  RCL_SET_ERROR_MSG("Argument does not use a valid severity level");
1807  ret = RCL_RET_ERROR;
1808  }
1809 
1810 cleanup:
1811  if (logger_name) {
1812  allocator->deallocate(logger_name, allocator->state);
1813  }
1814  rcl_ret_t rv = rcl_lexer_lookahead2_fini(&lex_lookahead);
1815  if (RCL_RET_OK != rv) {
1816  if (RCL_RET_OK != ret) {
1817  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1818  } else {
1819  ret = rv;
1820  }
1821  }
1822 
1823  return ret;
1824 }
1825 
1826 rcl_ret_t
1827 _rcl_parse_remap_rule(
1828  const char * arg,
1829  rcl_allocator_t allocator,
1830  rcl_remap_t * output_rule)
1831 {
1832  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1833  RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT);
1834 
1835  output_rule->impl =
1836  allocator.allocate(sizeof(rcl_remap_impl_t), allocator.state);
1837  if (NULL == output_rule->impl) {
1838  return RCL_RET_BAD_ALLOC;
1839  }
1840  output_rule->impl->allocator = allocator;
1841  output_rule->impl->type = RCL_UNKNOWN_REMAP;
1842  output_rule->impl->node_name = NULL;
1843  output_rule->impl->match = NULL;
1844  output_rule->impl->replacement = NULL;
1845 
1847  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, allocator);
1848 
1849  if (RCL_RET_OK == ret) {
1850  ret = _rcl_parse_remap_begin_remap_rule(&lex_lookahead, output_rule);
1851 
1852  rcl_ret_t fini_ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
1853  if (RCL_RET_OK != ret) {
1854  if (RCL_RET_OK != fini_ret) {
1855  RCUTILS_LOG_ERROR_NAMED(
1856  ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1857  }
1858  } else {
1859  if (RCL_RET_OK == fini_ret) {
1860  return RCL_RET_OK;
1861  }
1862  ret = fini_ret;
1863  }
1864  }
1865 
1866  // cleanup output rule but keep first error return code
1867  if (RCL_RET_OK != rcl_remap_fini(output_rule)) {
1868  RCUTILS_LOG_ERROR_NAMED(
1869  ROS_PACKAGE_NAME, "Failed to fini remap rule after error occurred");
1870  }
1871 
1872  return ret;
1873 }
1874 
1875 rcl_ret_t
1876 _rcl_parse_param_rule(
1877  const char * arg,
1878  rcl_params_t * params)
1879 {
1880  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1881  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
1882 
1884 
1885  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, params->allocator);
1886  if (RCL_RET_OK != ret) {
1887  return ret;
1888  }
1889 
1890  rcl_lexeme_t lexeme1;
1891  rcl_lexeme_t lexeme2;
1892  char * node_name = NULL;
1893  char * param_name = NULL;
1894 
1895  // Check for optional nodename prefix
1896  ret = rcl_lexer_lookahead2_peek2(&lex_lookahead, &lexeme1, &lexeme2);
1897  if (RCL_RET_OK != ret) {
1898  goto cleanup;
1899  }
1900 
1901  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1902  ret = _rcl_parse_nodename_prefix(&lex_lookahead, params->allocator, &node_name);
1903  if (RCL_RET_OK != ret) {
1904  if (RCL_RET_WRONG_LEXEME == ret) {
1906  }
1907  goto cleanup;
1908  }
1909  } else {
1910  node_name = rcutils_strdup("/**", params->allocator);
1911  if (NULL == node_name) {
1912  ret = RCL_RET_BAD_ALLOC;
1913  goto cleanup;
1914  }
1915  }
1916 
1917  // TODO(hidmic): switch to _rcl_parse_resource_match() when parameter names
1918  // are standardized to use slashes in lieu of dots.
1919  ret = _rcl_parse_param_name(&lex_lookahead, params->allocator, &param_name);
1920  if (RCL_RET_OK != ret) {
1921  if (RCL_RET_WRONG_LEXEME == ret) {
1923  }
1924  goto cleanup;
1925  }
1926 
1927  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1928  if (RCL_RET_WRONG_LEXEME == ret) {
1930  goto cleanup;
1931  }
1932 
1933  const char * yaml_value = rcl_lexer_lookahead2_get_text(&lex_lookahead);
1934  if (!rcl_parse_yaml_value(node_name, param_name, yaml_value, params)) {
1936  goto cleanup;
1937  }
1938 
1939 cleanup:
1940  params->allocator.deallocate(param_name, params->allocator.state);
1941  params->allocator.deallocate(node_name, params->allocator.state);
1942  if (RCL_RET_OK != ret) {
1943  if (RCL_RET_OK != rcl_lexer_lookahead2_fini(&lex_lookahead)) {
1944  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1945  }
1946  } else {
1947  ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
1948  }
1949  return ret;
1950 }
1951 
1952 rcl_ret_t
1953 _rcl_parse_param_file(
1954  const char * arg,
1955  rcl_allocator_t allocator,
1956  rcl_params_t * params,
1957  char ** param_file)
1958 {
1959  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1960  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
1961  RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT);
1962  *param_file = rcutils_strdup(arg, allocator);
1963  if (NULL == *param_file) {
1964  RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path");
1965  return RCL_RET_BAD_ALLOC;
1966  }
1967  if (!rcl_parse_yaml_file(*param_file, params)) {
1968  allocator.deallocate(*param_file, allocator.state);
1969  *param_file = NULL;
1970  // Error message already set.
1971  return RCL_RET_ERROR;
1972  }
1973  return RCL_RET_OK;
1974 }
1975 
1976 rcl_ret_t
1977 _rcl_parse_external_log_config_file(
1978  const char * arg,
1979  rcl_allocator_t allocator,
1980  char ** log_config_file)
1981 {
1982  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1983  RCL_CHECK_ARGUMENT_FOR_NULL(log_config_file, RCL_RET_INVALID_ARGUMENT);
1984 
1985  *log_config_file = rcutils_strdup(arg, allocator);
1986  // TODO(hidmic): add file checks
1987  if (NULL == *log_config_file) {
1988  RCL_SET_ERROR_MSG("Failed to allocate memory for external log config file");
1989  return RCL_RET_BAD_ALLOC;
1990  }
1991  return RCL_RET_OK;
1992 }
1993 
1994 rcl_ret_t
1995 _rcl_parse_enclave(
1996  const char * arg,
1997  rcl_allocator_t allocator,
1998  char ** enclave)
1999 {
2000  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2001  RCL_CHECK_ARGUMENT_FOR_NULL(enclave, RCL_RET_INVALID_ARGUMENT);
2002 
2003  *enclave = rcutils_strdup(arg, allocator);
2004  if (NULL == *enclave) {
2005  RCL_SET_ERROR_MSG("Failed to allocate memory for enclave name");
2006  return RCL_RET_BAD_ALLOC;
2007  }
2008  return RCL_RET_OK;
2009 }
2010 
2011 rcl_ret_t
2012 _rcl_parse_disabling_flag(
2013  const char * arg,
2014  const char * suffix,
2015  bool * disable)
2016 {
2017  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2018  RCL_CHECK_ARGUMENT_FOR_NULL(suffix, RCL_RET_INVALID_ARGUMENT);
2019  RCL_CHECK_ARGUMENT_FOR_NULL(disable, RCL_RET_INVALID_ARGUMENT);
2020 
2021  const size_t enable_prefix_len = strlen(RCL_ENABLE_FLAG_PREFIX);
2022  if (
2023  strncmp(RCL_ENABLE_FLAG_PREFIX, arg, enable_prefix_len) == 0 &&
2024  strcmp(suffix, arg + enable_prefix_len) == 0)
2025  {
2026  *disable = false;
2027  return RCL_RET_OK;
2028  }
2029 
2030  const size_t disable_prefix_len = strlen(RCL_DISABLE_FLAG_PREFIX);
2031  if (
2032  strncmp(RCL_DISABLE_FLAG_PREFIX, arg, disable_prefix_len) == 0 &&
2033  strcmp(suffix, arg + disable_prefix_len) == 0)
2034  {
2035  *disable = true;
2036  return RCL_RET_OK;
2037  }
2038 
2039  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
2040  "Argument is not a %s%s nor a %s%s flag.",
2041  RCL_ENABLE_FLAG_PREFIX, suffix,
2042  RCL_DISABLE_FLAG_PREFIX, suffix);
2043  return RCL_RET_ERROR;
2044 }
2045 
2046 rcl_ret_t
2047 _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator)
2048 {
2049  args->impl = allocator->allocate(sizeof(rcl_arguments_impl_t), allocator->state);
2050  if (NULL == args->impl) {
2051  return RCL_RET_BAD_ALLOC;
2052  }
2053 
2054  rcl_arguments_impl_t * args_impl = args->impl;
2055  args_impl->num_remap_rules = 0;
2056  args_impl->remap_rules = NULL;
2058  args_impl->external_log_config_file = NULL;
2059  args_impl->unparsed_args = NULL;
2060  args_impl->num_unparsed_args = 0;
2061  args_impl->unparsed_ros_args = NULL;
2062  args_impl->num_unparsed_ros_args = 0;
2063  args_impl->parameter_overrides = NULL;
2064  args_impl->parameter_files = NULL;
2065  args_impl->num_param_files_args = 0;
2066  args_impl->log_stdout_disabled = false;
2067  args_impl->log_rosout_disabled = false;
2068  args_impl->log_ext_lib_disabled = false;
2069  args_impl->enclave = NULL;
2070  args_impl->allocator = *allocator;
2071 
2072  return RCL_RET_OK;
2073 }
2074 
2075 #ifdef __cplusplus
2076 }
2077 #endif
2078 
#define RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, msg, fail_statement)
Check that the given allocator is initialized, or fail with a message.
Definition: allocator.h:56
rcutils_allocator_t rcl_allocator_t
Encapsulation of an allocator.
Definition: allocator.h:31
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_unparsed_ros(const rcl_arguments_t *args, rcl_allocator_t allocator, int **output_unparsed_ros_indices)
Return a list of indices to unknown ROS specific arguments that were left unparsed.
#define RCL_ROS_ARGS_EXPLICIT_END_TOKEN
The token that delineates the explicit end of ROS arguments.
Definition: arguments.h:45
RCL_PUBLIC RCL_WARN_UNUSED int rcl_arguments_get_count_unparsed(const rcl_arguments_t *args)
Return the number of arguments that were not ROS specific arguments.
#define RCL_LOG_LEVEL_FLAG
The ROS flag that precedes the ROS logging level to set.
Definition: arguments.h:69
#define RCL_LOG_ROSOUT_FLAG_SUFFIX
Definition: arguments.h:80
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_param_files(const rcl_arguments_t *arguments, rcl_allocator_t allocator, char ***parameter_files)
Return a list of yaml parameter file paths specified on the command line.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_copy(const rcl_arguments_t *args, rcl_arguments_t *args_out)
Copy one arguments structure into another.
#define RCL_PARAM_FLAG
The ROS flag that precedes the setting of a ROS parameter.
Definition: arguments.h:48
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_param_overrides(const rcl_arguments_t *arguments, rcl_params_t **parameter_overrides)
Return all parameter overrides parsed from the command line.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_log_levels(const rcl_arguments_t *arguments, rcl_log_levels_t *log_levels)
Return log levels parsed from the command line.
#define RCL_ROS_ARGS_FLAG
The command-line flag that delineates the start of ROS arguments.
Definition: arguments.h:42
#define RCL_LOG_EXT_LIB_FLAG_SUFFIX
Definition: arguments.h:84
#define RCL_SHORT_PARAM_FLAG
The short version of the ROS flag that precedes the setting of a ROS parameter.
Definition: arguments.h:51
#define RCL_ENCLAVE_FLAG
The ROS flag that precedes the name of a ROS security enclave.
Definition: arguments.h:63
#define RCL_LOG_STDOUT_FLAG_SUFFIX
Definition: arguments.h:76
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_parse_arguments(int argc, const char *const *argv, rcl_allocator_t allocator, rcl_arguments_t *args_output)
Parse command line arguments into a structure usable by code.
#define RCL_REMAP_FLAG
The ROS flag that precedes a ROS remapping rule.
Definition: arguments.h:57
#define RCL_EXTERNAL_LOG_CONFIG_FLAG
The ROS flag that precedes the name of a configuration file to configure logging.
Definition: arguments.h:72
#define RCL_SHORT_REMAP_FLAG
The short version of the ROS flag that precedes a ROS remapping rule.
Definition: arguments.h:60
#define RCL_SHORT_ENCLAVE_FLAG
The short version of the ROS flag that precedes the name of a ROS security enclave.
Definition: arguments.h:66
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_fini(rcl_arguments_t *args)
Reclaim resources held inside rcl_arguments_t structure.
RCL_PUBLIC RCL_WARN_UNUSED int rcl_arguments_get_param_files_count(const rcl_arguments_t *args)
Return the number of parameter yaml files given in the arguments.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_arguments_get_unparsed(const rcl_arguments_t *args, rcl_allocator_t allocator, int **output_unparsed_indices)
Return a list of indices to non ROS specific arguments.
RCL_PUBLIC RCL_WARN_UNUSED int rcl_arguments_get_count_unparsed_ros(const rcl_arguments_t *args)
Return the number of ROS specific arguments that were not successfully parsed.
#define RCL_PARAM_FILE_FLAG
The ROS flag that precedes a path to a file containing ROS parameters.
Definition: arguments.h:54
RCL_PUBLIC RCL_WARN_UNUSED rcl_arguments_t rcl_get_zero_initialized_arguments(void)
Return a rcl_arguments_t struct with members initialized to NULL.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_remove_ros_arguments(const char *const *argv, const rcl_arguments_t *args, rcl_allocator_t allocator, int *nonros_argc, const char ***nonros_argv)
Return a list of arguments with ROS-specific arguments removed.
@ RCL_LEXEME_WILD_ONE
Definition: lexer.h:76
@ RCL_LEXEME_NS
__ns
Definition: lexer.h:50
@ RCL_LEXEME_TOKEN
a name between slashes, must match (([a-zA-Z](_)?)|_)([0-9a-zA-Z](_)?)*
Definition: lexer.h:72
@ RCL_LEXEME_EOF
Indicates end of input has been reached.
Definition: lexer.h:38
@ RCL_LEXEME_URL_TOPIC
rostopic://
Definition: lexer.h:44
@ RCL_LEXEME_BR2
\2
Definition: lexer.h:56
@ RCL_LEXEME_BR8
\8
Definition: lexer.h:68
@ RCL_LEXEME_BR4
\4
Definition: lexer.h:60
@ RCL_LEXEME_BR9
\9
Definition: lexer.h:70
@ RCL_LEXEME_URL_SERVICE
rosservice://
Definition: lexer.h:42
@ RCL_LEXEME_BR1
\1
Definition: lexer.h:54
@ RCL_LEXEME_BR6
\6
Definition: lexer.h:64
@ RCL_LEXEME_TILDE_SLASH
~/
Definition: lexer.h:40
@ RCL_LEXEME_FORWARD_SLASH
/
Definition: lexer.h:74
@ RCL_LEXEME_SEPARATOR
:=
Definition: lexer.h:52
@ RCL_LEXEME_BR3
\3
Definition: lexer.h:58
@ RCL_LEXEME_BR5
\5
Definition: lexer.h:62
@ RCL_LEXEME_BR7
\7
Definition: lexer.h:66
@ RCL_LEXEME_NODE
__node or __name
Definition: lexer.h:48
@ RCL_LEXEME_DOT
.
Definition: lexer.h:82
@ RCL_LEXEME_WILD_MULTI
**
Definition: lexer.h:78
@ RCL_LEXEME_COLON
:
Definition: lexer.h:46
enum rcl_lexeme_e rcl_lexeme_t
Type of lexeme found by lexical analysis.
RCL_PUBLIC RCL_WARN_UNUSED rcl_lexer_lookahead2_t rcl_get_zero_initialized_lexer_lookahead2()
Get a zero initialized rcl_lexer_lookahead2_t instance.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_fini(rcl_lexer_lookahead2_t *buffer)
Finalize an instance of an rcl_lexer_lookahead2_t structure.
RCL_PUBLIC RCL_WARN_UNUSED const char * rcl_lexer_lookahead2_get_text(const rcl_lexer_lookahead2_t *buffer)
Get the text at the point where it is currently being analyzed.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_peek2(rcl_lexer_lookahead2_t *buffer, rcl_lexeme_t *next_type1, rcl_lexeme_t *next_type2)
Look ahead at the next two lexemes in the string.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_accept(rcl_lexer_lookahead2_t *buffer, const char **lexeme_text, size_t *lexeme_text_length)
Accept a lexeme and advance analysis.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_expect(rcl_lexer_lookahead2_t *buffer, rcl_lexeme_t type, const char **lexeme_text, size_t *lexeme_text_length)
Require the next lexeme to be a certain type and advance analysis.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_peek(rcl_lexer_lookahead2_t *buffer, rcl_lexeme_t *next_type)
Look ahead at the next lexeme in the string.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_lexer_lookahead2_init(rcl_lexer_lookahead2_t *buffer, const char *text, rcl_allocator_t allocator)
Initialize an rcl_lexer_lookahead2_t instance.
RCL_PUBLIC rcl_ret_t rcl_log_levels_fini(rcl_log_levels_t *log_levels)
Reclaim resources held inside rcl_log_levels_t structure.
Definition: log_level.c:102
enum RCUTILS_LOG_SEVERITY rcl_log_severity_t
typedef for RCUTILS_LOG_SEVERITY;
Definition: log_level.h:31
RCL_PUBLIC RCL_WARN_UNUSED rcl_log_levels_t rcl_get_zero_initialized_log_levels()
Return a rcl_log_levels_t struct with members initialized to zero value.
Definition: log_level.c:23
RCL_PUBLIC rcl_ret_t rcl_log_levels_add_logger_setting(rcl_log_levels_t *log_levels, const char *logger_name, rcl_log_severity_t log_level)
Add logger setting with a name and a level.
Definition: log_level.c:145
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_log_levels_init(rcl_log_levels_t *log_levels, const rcl_allocator_t *allocator, size_t logger_count)
Initialize a log levels structure.
Definition: log_level.c:36
RCL_PUBLIC rcl_ret_t rcl_log_levels_shrink_to_size(rcl_log_levels_t *log_levels)
Shrink log levels structure.
Definition: log_level.c:121
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_log_levels_copy(const rcl_log_levels_t *src, rcl_log_levels_t *dst)
Copy one log levels structure into another.
Definition: log_level.c:64
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_remap_fini(rcl_remap_t *remap)
Reclaim resources held inside rcl_remap_t structure.
Definition: remap.c:334
RCL_PUBLIC RCL_WARN_UNUSED rcl_remap_t rcl_get_zero_initialized_remap(void)
Return a rcl_remap_t struct with members initialized to NULL.
Definition: remap.c:32
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_remap_copy(const rcl_remap_t *rule, rcl_remap_t *rule_out)
Copy one remap structure into another.
Definition: remap.c:41
char * external_log_config_file
A file used to configure the external logging library.
rcl_log_levels_t log_levels
Log levels parsed from arguments.
rcl_params_t * parameter_overrides
Parameter override rules parsed from arguments.
int num_unparsed_args
Length of unparsed_args.
int num_param_files_args
Length of parameter_files.
bool log_rosout_disabled
A boolean value indicating if the rosout topic handler should be used for log output.
bool log_stdout_disabled
A boolean value indicating if the standard out handler should be used for log output.
rcl_allocator_t allocator
Allocator used to allocate objects in this struct.
int * unparsed_args
Array of indices to non-ROS arguments.
int * unparsed_ros_args
Array of indices to unknown ROS specific arguments.
char * enclave
Enclave to be used.
bool log_ext_lib_disabled
A boolean value indicating if the external lib handler should be used for log output.
rcl_remap_t * remap_rules
Array of rules for name remapping.
int num_remap_rules
Length of remap_rules.
int num_unparsed_ros_args
Length of unparsed_ros_args.
char ** parameter_files
Array of yaml parameter file paths.
Hold output of parsing command line arguments.
Definition: arguments.h:36
rcl_arguments_impl_t * impl
Private implementation pointer.
Definition: arguments.h:38
Track lexical analysis and allow looking ahead 2 lexemes.
Hold default logger level and other logger setting.
Definition: log_level.h:44
rcl_allocator_t allocator
Allocator used to allocate objects in this struct.
Definition: log_level.h:54
rcl_logger_setting_t * logger_settings
Array of logger setting.
Definition: log_level.h:48
rcl_log_severity_t default_logger_level
Minimum default logger level severity.
Definition: log_level.h:46
char * replacement
Replacement portion of a rule.
Definition: remap_impl.h:48
char * node_name
A node name that this rule is limited to, or NULL if it applies to any node.
Definition: remap_impl.h:44
rcl_allocator_t allocator
Allocator used to allocate objects in this struct.
Definition: remap_impl.h:51
char * match
Match portion of a rule, or NULL if node name or namespace replacement.
Definition: remap_impl.h:46
rcl_remap_type_t type
Bitmask indicating what type of rule this is.
Definition: remap_impl.h:42
Hold remapping rules.
Definition: remap.h:35
rcl_remap_impl_t * impl
Private implementation pointer.
Definition: remap.h:37
#define RCL_RET_INVALID_LOG_LEVEL_RULE
Argument is not a valid log level rule.
Definition: types.h:112
#define RCL_RET_INVALID_PARAM_RULE
Argument is not a valid parameter rule.
Definition: types.h:110
#define RCL_RET_WRONG_LEXEME
Expected one type of lexeme but got another.
Definition: types.h:106
#define RCL_RET_INVALID_ROS_ARGS
Found invalid ros argument while parsing.
Definition: types.h:108
#define RCL_RET_INVALID_REMAP_RULE
Argument is not a valid remap rule.
Definition: types.h:104
#define RCL_RET_OK
Success return code.
Definition: types.h:26
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:32
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:34
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:28
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:23