ROS 2 rclcpp + rcl - jazzy  jazzy
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 
37 
46 RCL_LOCAL
48 _rcl_parse_remap_rule(
49  const char * arg,
50  rcl_allocator_t allocator,
51  rcl_remap_t * output_rule);
52 
54 
65 _rcl_parse_param_rule(
66  const char * arg,
67  rcl_params_t * params);
68 
71  const rcl_arguments_t * arguments,
72  rcl_allocator_t allocator,
73  char *** parameter_files)
74 {
75  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
76  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
77  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
78  RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT);
79  *(parameter_files) = allocator.allocate(
80  sizeof(char *) * arguments->impl->num_param_files_args, allocator.state);
81  if (NULL == *parameter_files) {
82  return RCL_RET_BAD_ALLOC;
83  }
84  for (int i = 0; i < arguments->impl->num_param_files_args; ++i) {
85  (*parameter_files)[i] = rcutils_strdup(arguments->impl->parameter_files[i], allocator);
86  if (NULL == (*parameter_files)[i]) {
87  // deallocate allocated memory
88  for (int r = i; r >= 0; --r) {
89  allocator.deallocate((*parameter_files)[r], allocator.state);
90  }
91  allocator.deallocate((*parameter_files), allocator.state);
92  (*parameter_files) = NULL;
93  return RCL_RET_BAD_ALLOC;
94  }
95  }
96  return RCL_RET_OK;
97 }
98 
99 int
101  const rcl_arguments_t * args)
102 {
103  if (NULL == args || NULL == args->impl) {
104  return -1;
105  }
106  return args->impl->num_param_files_args;
107 }
108 
109 rcl_ret_t
111  const rcl_arguments_t * arguments,
112  rcl_params_t ** parameter_overrides)
113 {
114  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
115  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
116  RCL_CHECK_ARGUMENT_FOR_NULL(parameter_overrides, RCL_RET_INVALID_ARGUMENT);
117 
118  if (NULL != *parameter_overrides) {
119  RCL_SET_ERROR_MSG("Output parameter override pointer is not null. May leak memory.");
121  }
122  *parameter_overrides = NULL;
123  if (NULL != arguments->impl->parameter_overrides) {
124  *parameter_overrides = rcl_yaml_node_struct_copy(arguments->impl->parameter_overrides);
125  if (NULL == *parameter_overrides) {
126  return RCL_RET_BAD_ALLOC;
127  }
128  }
129  return RCL_RET_OK;
130 }
131 
132 rcl_ret_t
134  const rcl_arguments_t * arguments,
135  rcl_log_levels_t * log_levels)
136 {
137  RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
138  RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
139  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
140  const rcl_allocator_t * allocator = &arguments->impl->allocator;
141  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
142 
143  return rcl_log_levels_copy(&arguments->impl->log_levels, log_levels);
144 }
145 
147 
155 RCL_LOCAL
156 rcl_ret_t
157 _rcl_parse_log_level(
158  const char * arg,
159  rcl_log_levels_t * log_levels);
160 
162 
170 RCL_LOCAL
171 rcl_ret_t
172 _rcl_parse_external_log_file_name(
173  const char * arg,
174  rcl_allocator_t allocator,
175  char ** log_file_name_prefix);
176 
178 
186 RCL_LOCAL
187 rcl_ret_t
188 _rcl_parse_external_log_config_file(
189  const char * arg,
190  rcl_allocator_t allocator,
191  char ** log_config_file);
192 
194 
204 RCL_LOCAL
205 rcl_ret_t
206 _rcl_parse_param_file(
207  const char * arg,
208  rcl_allocator_t allocator,
209  rcl_params_t * params,
210  char ** param_file);
211 
213 
221 RCL_LOCAL
222 rcl_ret_t
223 _rcl_parse_enclave(
224  const char * arg,
225  rcl_allocator_t allocator,
226  char ** enclave);
227 
228 #define RCL_ENABLE_FLAG_PREFIX "--enable-"
229 #define RCL_DISABLE_FLAG_PREFIX "--disable-"
230 
232 
239 RCL_LOCAL
240 rcl_ret_t
241 _rcl_parse_disabling_flag(
242  const char * arg,
243  const char * key,
244  bool * value);
245 
247 
253 rcl_ret_t
254 _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator);
255 
256 rcl_ret_t
258  int argc,
259  const char * const * argv,
260  rcl_allocator_t allocator,
261  rcl_arguments_t * args_output)
262 {
263  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
264  if (argc < 0) {
265  RCL_SET_ERROR_MSG("Argument count cannot be negative");
267  } else if (argc > 0) {
268  RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
269  }
270  RCL_CHECK_ARGUMENT_FOR_NULL(args_output, RCL_RET_INVALID_ARGUMENT);
271 
272  if (args_output->impl != NULL) {
273  RCL_SET_ERROR_MSG("Parse output is not zero-initialized");
275  }
276 
277  rcl_ret_t ret;
278  rcl_ret_t fail_ret;
279 
280  ret = _rcl_allocate_initialized_arguments_impl(args_output, &allocator);
281  if (RCL_RET_OK != ret) {
282  return ret;
283  }
284  rcl_arguments_impl_t * args_impl = args_output->impl;
285 
286  if (argc == 0) {
287  // there are no arguments to parse
288  return RCL_RET_OK;
289  }
290 
291  // over-allocate arrays to match the number of arguments
292  args_impl->remap_rules = allocator.allocate(sizeof(rcl_remap_t) * argc, allocator.state);
293  if (NULL == args_impl->remap_rules) {
294  ret = RCL_RET_BAD_ALLOC;
295  goto fail;
296  }
297 
298  args_impl->parameter_overrides = rcl_yaml_node_struct_init(allocator);
299  if (NULL == args_impl->parameter_overrides) {
300  ret = RCL_RET_BAD_ALLOC;
301  goto fail;
302  }
303 
304  args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state);
305  if (NULL == args_impl->parameter_files) {
306  ret = RCL_RET_BAD_ALLOC;
307  goto fail;
308  }
309  args_impl->unparsed_ros_args = allocator.allocate(sizeof(int) * argc, allocator.state);
310  if (NULL == args_impl->unparsed_ros_args) {
311  ret = RCL_RET_BAD_ALLOC;
312  goto fail;
313  }
314  args_impl->unparsed_args = allocator.allocate(sizeof(int) * argc, allocator.state);
315  if (NULL == args_impl->unparsed_args) {
316  ret = RCL_RET_BAD_ALLOC;
317  goto fail;
318  }
320  ret = rcl_log_levels_init(&log_levels, &allocator, argc);
321  if (ret != RCL_RET_OK) {
322  goto fail;
323  }
324  args_impl->log_levels = log_levels;
325 
326  bool parsing_ros_args = false;
327  for (int i = 0; i < argc; ++i) {
328  if (parsing_ros_args) {
329  // Ignore ROS specific arguments flags
330  if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
331  continue;
332  }
333 
334  // Check for ROS specific arguments explicit end token
335  if (strcmp(RCL_ROS_ARGS_EXPLICIT_END_TOKEN, argv[i]) == 0) {
336  parsing_ros_args = false;
337  continue;
338  }
339 
340  // Attempt to parse argument as parameter override flag
341  if (strcmp(RCL_PARAM_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_PARAM_FLAG, argv[i]) == 0) {
342  if (i + 1 < argc) {
343  // Attempt to parse next argument as parameter override rule
344  if (RCL_RET_OK == _rcl_parse_param_rule(argv[i + 1], args_impl->parameter_overrides)) {
345  RCUTILS_LOG_DEBUG_NAMED(
346  ROS_PACKAGE_NAME, "Got param override rule : %s\n", argv[i + 1]);
347  ++i; // Skip flag here, for loop will skip rule.
348  continue;
349  }
350  rcl_error_string_t prev_error_string = rcl_get_error_string();
351  rcl_reset_error();
352  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
353  "Couldn't parse parameter override rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
354  prev_error_string.str);
355  } else {
356  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
357  "Couldn't parse trailing %s flag. No parameter override rule found.", argv[i]);
358  }
360  goto fail;
361  }
362  RCUTILS_LOG_DEBUG_NAMED(
363  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
364  i, argv[i], RCL_PARAM_FLAG, RCL_SHORT_PARAM_FLAG);
365 
366  // Attempt to parse argument as remap rule flag
367  if (strcmp(RCL_REMAP_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_REMAP_FLAG, argv[i]) == 0) {
368  if (i + 1 < argc) {
369  // Attempt to parse next argument as remap rule
370  rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
372  if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i + 1], allocator, rule)) {
373  ++(args_impl->num_remap_rules);
374  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
375  ++i; // Skip flag here, for loop will skip rule.
376  continue;
377  }
378  rcl_error_string_t prev_error_string = rcl_get_error_string();
379  rcl_reset_error();
380  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
381  "Couldn't parse remap rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
382  prev_error_string.str);
383  } else {
384  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
385  "Couldn't parse trailing %s flag. No remap rule found.", argv[i]);
386  }
388  goto fail;
389  }
390  RCUTILS_LOG_DEBUG_NAMED(
391  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
392  i, argv[i], RCL_REMAP_FLAG, RCL_SHORT_REMAP_FLAG);
393 
394  // Attempt to parse argument as parameter file rule
395  if (strcmp(RCL_PARAM_FILE_FLAG, argv[i]) == 0) {
396  if (i + 1 < argc) {
397  // Attempt to parse next argument as parameter file rule
398  args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
399  if (
400  RCL_RET_OK == _rcl_parse_param_file(
401  argv[i + 1], allocator, args_impl->parameter_overrides,
402  &args_impl->parameter_files[args_impl->num_param_files_args]))
403  {
404  ++(args_impl->num_param_files_args);
405  RCUTILS_LOG_DEBUG_NAMED(
406  ROS_PACKAGE_NAME,
407  "Got params file : %s\ntotal num param files %d",
408  args_impl->parameter_files[args_impl->num_param_files_args - 1],
409  args_impl->num_param_files_args);
410  ++i; // Skip flag here, for loop will skip rule.
411  continue;
412  }
413  rcl_error_string_t prev_error_string = rcl_get_error_string();
414  rcl_reset_error();
415  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
416  "Couldn't parse params file: '%s %s'. Error: %s", argv[i], argv[i + 1],
417  prev_error_string.str);
418  } else {
419  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
420  "Couldn't parse trailing %s flag. No file path provided.", argv[i]);
421  }
423  goto fail;
424  }
425  RCUTILS_LOG_DEBUG_NAMED(
426  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
427  i, argv[i], RCL_PARAM_FILE_FLAG);
428 
429  // Attempt to parse argument as log level configuration
430  if (strcmp(RCL_LOG_LEVEL_FLAG, argv[i]) == 0) {
431  if (i + 1 < argc) {
432  if (RCL_RET_OK ==
433  _rcl_parse_log_level(argv[i + 1], &args_impl->log_levels))
434  {
435  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got log level: %s\n", argv[i + 1]);
436  ++i; // Skip flag here, for loop will skip value.
437  continue;
438  }
439  rcl_error_string_t prev_error_string = rcl_get_error_string();
440  rcl_reset_error();
441  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
442  "Couldn't parse log level: '%s %s'. Error: %s", argv[i], argv[i + 1],
443  prev_error_string.str);
444  } else {
445  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
446  "Couldn't parse trailing log level flag: '%s'. No log level provided.", argv[i]);
447  }
449  goto fail;
450  }
451  RCUTILS_LOG_DEBUG_NAMED(
452  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
453  i, argv[i], RCL_LOG_LEVEL_FLAG);
454 
455  // Attempt to parse argument as external log file name prefix
456  if (strcmp(RCL_EXTERNAL_LOG_FILE_NAME_PREFIX, argv[i]) == 0) {
457  if (i + 1 < argc) {
458  if (NULL != args_impl->external_log_file_name_prefix) {
459  RCUTILS_LOG_DEBUG_NAMED(
460  ROS_PACKAGE_NAME, "Overriding log file name : %s\n",
461  args_impl->external_log_file_name_prefix);
462  allocator.deallocate(args_impl->external_log_file_name_prefix, allocator.state);
463  args_impl->external_log_file_name_prefix = NULL;
464  }
465  if (RCL_RET_OK == _rcl_parse_external_log_file_name(
466  argv[i + 1], allocator, &args_impl->external_log_file_name_prefix))
467  {
468  RCUTILS_LOG_DEBUG_NAMED(
469  ROS_PACKAGE_NAME, "Got log file name prefix : %s\n",
470  args_impl->external_log_file_name_prefix);
471  ++i; // Skip flag here, for loop will skip value.
472  continue;
473  }
474  rcl_error_string_t prev_error_string = rcl_get_error_string();
475  rcl_reset_error();
476  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
477  "Couldn't parse log file name prefix: '%s %s'. Error: %s", argv[i], argv[i + 1],
478  prev_error_string.str);
479  } else {
480  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
481  "Couldn't parse trailing %s flag. No string prefix provided.", argv[i]);
482  }
484  goto fail;
485  }
486  RCUTILS_LOG_DEBUG_NAMED(
487  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
489 
490  // Attempt to parse argument as log configuration file
491  if (strcmp(RCL_EXTERNAL_LOG_CONFIG_FLAG, argv[i]) == 0) {
492  if (i + 1 < argc) {
493  if (NULL != args_impl->external_log_config_file) {
494  RCUTILS_LOG_DEBUG_NAMED(
495  ROS_PACKAGE_NAME, "Overriding log configuration file : %s\n",
496  args_impl->external_log_config_file);
497  allocator.deallocate(args_impl->external_log_config_file, allocator.state);
498  args_impl->external_log_config_file = NULL;
499  }
500  if (RCL_RET_OK == _rcl_parse_external_log_config_file(
501  argv[i + 1], allocator, &args_impl->external_log_config_file))
502  {
503  RCUTILS_LOG_DEBUG_NAMED(
504  ROS_PACKAGE_NAME, "Got log configuration file : %s\n",
505  args_impl->external_log_config_file);
506  ++i; // Skip flag here, for loop will skip value.
507  continue;
508  }
509  rcl_error_string_t prev_error_string = rcl_get_error_string();
510  rcl_reset_error();
511  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
512  "Couldn't parse log configuration file: '%s %s'. Error: %s", argv[i], argv[i + 1],
513  prev_error_string.str);
514  } else {
515  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
516  "Couldn't parse trailing %s flag. No file path provided.", argv[i]);
517  }
519  goto fail;
520  }
521  RCUTILS_LOG_DEBUG_NAMED(
522  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
523  i, argv[i], RCL_EXTERNAL_LOG_CONFIG_FLAG);
524 
525  // Attempt to parse argument as a security enclave
526  if (strcmp(RCL_ENCLAVE_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_ENCLAVE_FLAG, argv[i]) == 0) {
527  if (i + 1 < argc) {
528  if (NULL != args_impl->enclave) {
529  RCUTILS_LOG_DEBUG_NAMED(
530  ROS_PACKAGE_NAME, "Overriding security enclave : %s\n",
531  args_impl->enclave);
532  allocator.deallocate(args_impl->enclave, allocator.state);
533  args_impl->enclave = NULL;
534  }
535  if (RCL_RET_OK == _rcl_parse_enclave(
536  argv[i + 1], allocator, &args_impl->enclave))
537  {
538  RCUTILS_LOG_DEBUG_NAMED(
539  ROS_PACKAGE_NAME, "Got enclave: %s\n",
540  args_impl->enclave);
541  ++i; // Skip flag here, for loop will skip value.
542  continue;
543  }
544  rcl_error_string_t prev_error_string = rcl_get_error_string();
545  rcl_reset_error();
546  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
547  "Couldn't parse enclave name: '%s %s'. Error: %s", argv[i], argv[i + 1],
548  prev_error_string.str);
549  } else {
550  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
551  "Couldn't parse trailing %s flag. No enclave path provided.", argv[i]);
552  }
554  goto fail;
555  }
556  RCUTILS_LOG_DEBUG_NAMED(
557  ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
558  i, argv[i], RCL_ENCLAVE_FLAG);
559 
560  // Attempt to parse --enable/disable-stdout-logs flag
561  ret = _rcl_parse_disabling_flag(
562  argv[i], RCL_LOG_STDOUT_FLAG_SUFFIX, &args_impl->log_stdout_disabled);
563  if (RCL_RET_OK == ret) {
564  RCUTILS_LOG_DEBUG_NAMED(
565  ROS_PACKAGE_NAME, "Disable log stdout ? %s\n",
566  args_impl->log_stdout_disabled ? "true" : "false");
567  continue;
568  }
569  RCUTILS_LOG_DEBUG_NAMED(
570  ROS_PACKAGE_NAME,
571  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
572  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX,
573  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX, rcl_get_error_string().str);
574  rcl_reset_error();
575 
576  // Attempt to parse --enable/disable-rosout-logs flag
577  ret = _rcl_parse_disabling_flag(
578  argv[i], RCL_LOG_ROSOUT_FLAG_SUFFIX, &args_impl->log_rosout_disabled);
579  if (RCL_RET_OK == ret) {
580  RCUTILS_LOG_DEBUG_NAMED(
581  ROS_PACKAGE_NAME, "Disable log rosout ? %s\n",
582  args_impl->log_rosout_disabled ? "true" : "false");
583  continue;
584  }
585  RCUTILS_LOG_DEBUG_NAMED(
586  ROS_PACKAGE_NAME,
587  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
588  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX,
589  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX, rcl_get_error_string().str);
590  rcl_reset_error();
591 
592  // Attempt to parse --enable/disable-external-lib-logs flag
593  ret = _rcl_parse_disabling_flag(
594  argv[i], RCL_LOG_EXT_LIB_FLAG_SUFFIX, &args_impl->log_ext_lib_disabled);
595  if (RCL_RET_OK == ret) {
596  RCUTILS_LOG_DEBUG_NAMED(
597  ROS_PACKAGE_NAME, "Disable log external lib ? %s\n",
598  args_impl->log_ext_lib_disabled ? "true" : "false");
599  continue;
600  }
601  RCUTILS_LOG_DEBUG_NAMED(
602  ROS_PACKAGE_NAME,
603  "Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
604  i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX,
605  RCL_DISABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX, rcl_get_error_string().str);
606  rcl_reset_error();
607 
608  // Argument is an unknown ROS specific argument
609  args_impl->unparsed_ros_args[args_impl->num_unparsed_ros_args] = i;
610  ++(args_impl->num_unparsed_ros_args);
611  } else {
612  // Check for ROS specific arguments flags
613  if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
614  parsing_ros_args = true;
615  continue;
616  }
617 
618  // Attempt to parse argument as remap rule in its deprecated form
619  rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
621  if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) {
622  RCUTILS_LOG_WARN_NAMED(
623  ROS_PACKAGE_NAME,
624  "Found remap rule '%s'. This syntax is deprecated. Use '%s %s %s' instead.",
625  argv[i], RCL_ROS_ARGS_FLAG, RCL_REMAP_FLAG, argv[i]);
626  RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
627  ++(args_impl->num_remap_rules);
628  continue;
629  }
630  RCUTILS_LOG_DEBUG_NAMED(
631  ROS_PACKAGE_NAME,
632  "Couldn't parse arg %d (%s) as a remap rule in its deprecated form. Error: %s",
633  i, argv[i], rcl_get_error_string().str);
634  rcl_reset_error();
635 
636  // Argument is not a ROS specific argument
637  args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
638  ++(args_impl->num_unparsed_args);
639  }
640  }
641 
642  // Shrink remap_rules array to match number of successfully parsed rules
643  if (0 == args_impl->num_remap_rules) {
644  // No remap rules
645  allocator.deallocate(args_impl->remap_rules, allocator.state);
646  args_impl->remap_rules = NULL;
647  } else if (args_impl->num_remap_rules < argc) {
648  rcl_remap_t * new_remap_rules = allocator.reallocate(
649  args_impl->remap_rules,
650  sizeof(rcl_remap_t) * args_impl->num_remap_rules,
651  &allocator);
652  if (NULL == new_remap_rules) {
653  ret = RCL_RET_BAD_ALLOC;
654  goto fail;
655  }
656  args_impl->remap_rules = new_remap_rules;
657  }
658 
659  // Shrink Parameter files
660  if (0 == args_impl->num_param_files_args) {
661  allocator.deallocate(args_impl->parameter_files, allocator.state);
662  args_impl->parameter_files = NULL;
663  } else if (args_impl->num_param_files_args < argc) {
664  char ** new_parameter_files = allocator.reallocate(
665  args_impl->parameter_files,
666  sizeof(char *) * args_impl->num_param_files_args,
667  &allocator);
668  if (NULL == new_parameter_files) {
669  ret = RCL_RET_BAD_ALLOC;
670  goto fail;
671  }
672  args_impl->parameter_files = new_parameter_files;
673  }
674 
675  // Drop parameter overrides if none was found.
676  if (0U == args_impl->parameter_overrides->num_nodes) {
677  rcl_yaml_node_struct_fini(args_impl->parameter_overrides);
678  args_impl->parameter_overrides = NULL;
679  }
680 
681  // Shrink unparsed_ros_args
682  if (0 == args_impl->num_unparsed_ros_args) {
683  // No unparsed ros args
684  allocator.deallocate(args_impl->unparsed_ros_args, allocator.state);
685  args_impl->unparsed_ros_args = NULL;
686  } else if (args_impl->num_unparsed_ros_args < argc) {
687  args_impl->unparsed_ros_args = rcutils_reallocf(
688  args_impl->unparsed_ros_args, sizeof(int) * args_impl->num_unparsed_ros_args, &allocator);
689  if (NULL == args_impl->unparsed_ros_args) {
690  ret = RCL_RET_BAD_ALLOC;
691  goto fail;
692  }
693  }
694 
695  // Shrink unparsed_args
696  if (0 == args_impl->num_unparsed_args) {
697  // No unparsed args
698  allocator.deallocate(args_impl->unparsed_args, allocator.state);
699  args_impl->unparsed_args = NULL;
700  } else if (args_impl->num_unparsed_args < argc) {
701  args_impl->unparsed_args = rcutils_reallocf(
702  args_impl->unparsed_args, sizeof(int) * args_impl->num_unparsed_args, &allocator);
703  if (NULL == args_impl->unparsed_args) {
704  ret = RCL_RET_BAD_ALLOC;
705  goto fail;
706  }
707  }
708 
709  // Shrink logger settings of log levels
710  ret = rcl_log_levels_shrink_to_size(&args_impl->log_levels);
711  if (ret != RCL_RET_OK) {
712  goto fail;
713  }
714 
715  return RCL_RET_OK;
716 fail:
717  fail_ret = ret;
718  if (NULL != args_impl) {
719  ret = rcl_arguments_fini(args_output);
720  if (RCL_RET_OK != ret) {
721  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini arguments after earlier failure");
722  }
723  }
724  return fail_ret;
725 }
726 
727 int
729  const rcl_arguments_t * args)
730 {
731  if (NULL == args || NULL == args->impl) {
732  return -1;
733  }
734  return args->impl->num_unparsed_args;
735 }
736 
737 rcl_ret_t
739  const rcl_arguments_t * args,
740  rcl_allocator_t allocator,
741  int ** output_unparsed_indices)
742 {
743  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
744  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
745  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
746  RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_indices, RCL_RET_INVALID_ARGUMENT);
747 
748  *output_unparsed_indices = NULL;
749  if (args->impl->num_unparsed_args) {
750  *output_unparsed_indices = allocator.allocate(
751  sizeof(int) * args->impl->num_unparsed_args, allocator.state);
752  if (NULL == *output_unparsed_indices) {
753  return RCL_RET_BAD_ALLOC;
754  }
755  for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
756  (*output_unparsed_indices)[i] = args->impl->unparsed_args[i];
757  }
758  }
759  return RCL_RET_OK;
760 }
761 
762 int
764  const rcl_arguments_t * args)
765 {
766  if (NULL == args || NULL == args->impl) {
767  return -1;
768  }
769  return args->impl->num_unparsed_ros_args;
770 }
771 
772 rcl_ret_t
774  const rcl_arguments_t * args,
775  rcl_allocator_t allocator,
776  int ** output_unparsed_ros_indices)
777 {
778  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
779  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
780  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
781  RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_ros_indices, RCL_RET_INVALID_ARGUMENT);
782 
783  *output_unparsed_ros_indices = NULL;
784  if (args->impl->num_unparsed_ros_args) {
785  *output_unparsed_ros_indices = allocator.allocate(
786  sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
787  if (NULL == *output_unparsed_ros_indices) {
788  return RCL_RET_BAD_ALLOC;
789  }
790  for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
791  (*output_unparsed_ros_indices)[i] = args->impl->unparsed_ros_args[i];
792  }
793  }
794  return RCL_RET_OK;
795 }
796 
799 {
800  static rcl_arguments_t default_arguments = {
801  .impl = NULL
802  };
803  return default_arguments;
804 }
805 
806 rcl_ret_t
808  const char * const * argv,
809  const rcl_arguments_t * args,
810  rcl_allocator_t allocator,
811  int * nonros_argc,
812  const char *** nonros_argv)
813 {
814  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
815  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
816  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT);
817  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argv, RCL_RET_INVALID_ARGUMENT);
818  if (NULL != *nonros_argv) {
819  RCL_SET_ERROR_MSG("Output nonros_argv pointer is not null. May leak memory.");
821  }
822 
823  *nonros_argc = rcl_arguments_get_count_unparsed(args);
824  if (*nonros_argc < 0) {
825  RCL_SET_ERROR_MSG("Failed to get unparsed non ROS specific arguments count.");
827  } else if (*nonros_argc > 0) {
828  RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
829  }
830 
831  *nonros_argv = NULL;
832  if (0 == *nonros_argc) {
833  return RCL_RET_OK;
834  }
835 
836  int * unparsed_indices = NULL;
837  rcl_ret_t ret = rcl_arguments_get_unparsed(args, allocator, &unparsed_indices);
838 
839  if (RCL_RET_OK != ret) {
840  return ret;
841  }
842 
843  size_t alloc_size = sizeof(char *) * *nonros_argc;
844  *nonros_argv = allocator.allocate(alloc_size, allocator.state);
845  if (NULL == *nonros_argv) {
846  allocator.deallocate(unparsed_indices, allocator.state);
847  return RCL_RET_BAD_ALLOC;
848  }
849  for (int i = 0; i < *nonros_argc; ++i) {
850  (*nonros_argv)[i] = argv[unparsed_indices[i]];
851  }
852 
853  allocator.deallocate(unparsed_indices, allocator.state);
854  return RCL_RET_OK;
855 }
856 
857 rcl_ret_t
859  const rcl_arguments_t * args,
860  rcl_arguments_t * args_out)
861 {
862  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
863  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
864 
865  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
866  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
867  RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
868  if (NULL != args_out->impl) {
869  RCL_SET_ERROR_MSG("args_out must be zero initialized");
871  }
872 
873  rcl_allocator_t allocator = args->impl->allocator;
874 
875  rcl_ret_t ret = _rcl_allocate_initialized_arguments_impl(args_out, &allocator);
876  if (RCL_RET_OK != ret) {
877  return ret;
878  }
879 
880  if (args->impl->num_unparsed_args) {
881  // Copy unparsed args
882  args_out->impl->unparsed_args = allocator.allocate(
883  sizeof(int) * args->impl->num_unparsed_args, allocator.state);
884  if (NULL == args_out->impl->unparsed_args) {
885  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
886  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
887  }
888  return RCL_RET_BAD_ALLOC;
889  }
890  for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
891  args_out->impl->unparsed_args[i] = args->impl->unparsed_args[i];
892  }
893  args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
894  }
895 
896  if (args->impl->num_unparsed_ros_args) {
897  // Copy unparsed ROS args
898  args_out->impl->unparsed_ros_args = allocator.allocate(
899  sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
900  if (NULL == args_out->impl->unparsed_ros_args) {
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_unparsed_ros_args; ++i) {
907  args_out->impl->unparsed_ros_args[i] = args->impl->unparsed_ros_args[i];
908  }
910  }
911 
912  if (args->impl->num_remap_rules) {
913  // Copy remap rules
914  args_out->impl->remap_rules = allocator.allocate(
915  sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state);
916  if (NULL == args_out->impl->remap_rules) {
917  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
918  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
919  }
920  return RCL_RET_BAD_ALLOC;
921  }
922  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
924  ret = rcl_remap_copy(
925  &(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i]));
926  if (RCL_RET_OK != ret) {
927  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
928  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
929  }
930  return ret;
931  }
932  ++(args_out->impl->num_remap_rules);
933  }
934  }
935 
936  // Copy parameter rules
937  if (args->impl->parameter_overrides) {
938  args_out->impl->parameter_overrides =
939  rcl_yaml_node_struct_copy(args->impl->parameter_overrides);
940  }
941 
942  // Copy parameter files
943  if (args->impl->num_param_files_args) {
944  args_out->impl->parameter_files = allocator.zero_allocate(
945  args->impl->num_param_files_args, sizeof(char *), allocator.state);
946  if (NULL == args_out->impl->parameter_files) {
947  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
948  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
949  }
950  return RCL_RET_BAD_ALLOC;
951  }
952  for (int i = 0; i < args->impl->num_param_files_args; ++i) {
953  args_out->impl->parameter_files[i] =
954  rcutils_strdup(args->impl->parameter_files[i], allocator);
955  if (NULL == args_out->impl->parameter_files[i]) {
956  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
957  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
958  }
959  return RCL_RET_BAD_ALLOC;
960  }
961  ++(args_out->impl->num_param_files_args);
962  }
963  }
964  char * enclave_copy = rcutils_strdup(args->impl->enclave, allocator);
965  if (args->impl->enclave && !enclave_copy) {
966  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
967  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
968  } else {
969  RCL_SET_ERROR_MSG("Error while copying enclave argument");
970  }
971  return RCL_RET_BAD_ALLOC;
972  }
973  args_out->impl->enclave = enclave_copy;
974  return RCL_RET_OK;
975 }
976 
977 rcl_ret_t
979  rcl_arguments_t * args)
980 {
981  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
982  if (args->impl) {
983  rcl_ret_t ret = RCL_RET_OK;
984  if (args->impl->remap_rules) {
985  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
986  rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i]));
987  if (remap_ret != RCL_RET_OK) {
988  ret = remap_ret;
989  RCUTILS_LOG_ERROR_NAMED(
990  ROS_PACKAGE_NAME,
991  "Failed to finalize remap rule while finalizing arguments. Continuing...");
992  }
993  }
994  args->impl->allocator.deallocate(args->impl->remap_rules, args->impl->allocator.state);
995  args->impl->remap_rules = NULL;
996  args->impl->num_remap_rules = 0;
997  }
998 
999  rcl_ret_t log_levels_ret = rcl_log_levels_fini(&args->impl->log_levels);
1000  if (log_levels_ret != RCL_RET_OK) {
1001  ret = log_levels_ret;
1002  RCUTILS_LOG_ERROR_NAMED(
1003  ROS_PACKAGE_NAME,
1004  "Failed to finalize log levels while finalizing arguments. Continuing...");
1005  }
1006 
1007  args->impl->allocator.deallocate(args->impl->unparsed_args, args->impl->allocator.state);
1008  args->impl->num_unparsed_args = 0;
1009  args->impl->unparsed_args = NULL;
1010 
1011  args->impl->allocator.deallocate(args->impl->unparsed_ros_args, args->impl->allocator.state);
1012  args->impl->num_unparsed_ros_args = 0;
1013  args->impl->unparsed_ros_args = NULL;
1014 
1015  if (args->impl->parameter_overrides) {
1016  rcl_yaml_node_struct_fini(args->impl->parameter_overrides);
1017  args->impl->parameter_overrides = NULL;
1018  }
1019 
1020  if (args->impl->parameter_files) {
1021  for (int p = 0; p < args->impl->num_param_files_args; ++p) {
1022  args->impl->allocator.deallocate(
1023  args->impl->parameter_files[p], args->impl->allocator.state);
1024  }
1025  args->impl->allocator.deallocate(args->impl->parameter_files, args->impl->allocator.state);
1026  args->impl->num_param_files_args = 0;
1027  args->impl->parameter_files = NULL;
1028  }
1029  args->impl->allocator.deallocate(args->impl->enclave, args->impl->allocator.state);
1030 
1031  if (NULL != args->impl->external_log_file_name_prefix) {
1032  args->impl->allocator.deallocate(
1033  args->impl->external_log_file_name_prefix, args->impl->allocator.state);
1034  args->impl->external_log_file_name_prefix = NULL;
1035  }
1036 
1037  if (NULL != args->impl->external_log_config_file) {
1038  args->impl->allocator.deallocate(
1039  args->impl->external_log_config_file, args->impl->allocator.state);
1040  args->impl->external_log_config_file = NULL;
1041  }
1042 
1043  args->impl->allocator.deallocate(args->impl, args->impl->allocator.state);
1044  args->impl = NULL;
1045  return ret;
1046  }
1047  RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice");
1048  return RCL_RET_ERROR;
1049 }
1050 
1052 
1055 RCL_LOCAL
1056 rcl_ret_t
1057 _rcl_parse_remap_fully_qualified_namespace(
1058  rcl_lexer_lookahead2_t * lex_lookahead)
1059 {
1060  rcl_ret_t ret;
1061 
1062  // Check arguments sanity
1063  assert(NULL != lex_lookahead);
1064 
1065  // Must have at least one Forward slash /
1066  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1067  if (RCL_RET_WRONG_LEXEME == ret) {
1069  }
1070 
1071  // repeated tokens and slashes (allow trailing slash, but don't require it)
1072  while (true) {
1073  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, NULL, NULL);
1074  if (RCL_RET_WRONG_LEXEME == ret) {
1075  rcl_reset_error();
1076  break;
1077  }
1078  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1079  if (RCL_RET_WRONG_LEXEME == ret) {
1080  rcl_reset_error();
1081  break;
1082  }
1083  }
1084  return RCL_RET_OK;
1085 }
1086 
1088 
1091 RCL_LOCAL
1092 rcl_ret_t
1093 _rcl_parse_remap_replacement_token(rcl_lexer_lookahead2_t * lex_lookahead)
1094 {
1095  rcl_ret_t ret;
1096  rcl_lexeme_t lexeme;
1097 
1098  // Check arguments sanity
1099  assert(NULL != lex_lookahead);
1100 
1101  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1102  if (RCL_RET_OK != ret) {
1103  return ret;
1104  }
1105 
1106  if (
1107  RCL_LEXEME_BR1 == lexeme || RCL_LEXEME_BR2 == lexeme || RCL_LEXEME_BR3 == lexeme ||
1108  RCL_LEXEME_BR4 == lexeme || RCL_LEXEME_BR5 == lexeme || RCL_LEXEME_BR6 == lexeme ||
1109  RCL_LEXEME_BR7 == lexeme || RCL_LEXEME_BR8 == lexeme || RCL_LEXEME_BR9 == lexeme)
1110  {
1111  RCL_SET_ERROR_MSG("Backreferences are not implemented");
1112  return RCL_RET_ERROR;
1113  } else if (RCL_LEXEME_TOKEN == lexeme) {
1114  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1115  } else {
1117  }
1118 
1119  return ret;
1120 }
1121 
1123 
1126 RCL_LOCAL
1127 rcl_ret_t
1128 _rcl_parse_remap_replacement_name(
1129  rcl_lexer_lookahead2_t * lex_lookahead,
1130  rcl_remap_t * rule)
1131 {
1132  rcl_ret_t ret;
1133  rcl_lexeme_t lexeme;
1134 
1135  // Check arguments sanity
1136  assert(NULL != lex_lookahead);
1137  assert(NULL != rule);
1138 
1139  const char * replacement_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1140  if (NULL == replacement_start) {
1141  RCL_SET_ERROR_MSG("failed to get start of replacement");
1142  return RCL_RET_ERROR;
1143  }
1144 
1145  // private name (~/...) or fully qualified name (/...) ?
1146  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1147  if (RCL_RET_OK != ret) {
1148  return ret;
1149  }
1150  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1151  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1152  }
1153  if (RCL_RET_OK != ret) {
1154  return ret;
1155  }
1156 
1157  // token ( '/' token )*
1158  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1159  if (RCL_RET_OK != ret) {
1160  return ret;
1161  }
1162  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1163  if (RCL_RET_OK != ret) {
1164  return ret;
1165  }
1166  while (RCL_LEXEME_EOF != lexeme) {
1167  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1168  if (RCL_RET_WRONG_LEXEME == ret) {
1170  }
1171  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1172  if (RCL_RET_OK != ret) {
1173  return ret;
1174  }
1175  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1176  if (RCL_RET_OK != ret) {
1177  return ret;
1178  }
1179  }
1180 
1181  // Copy replacement into rule
1182  const char * replacement_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1183  size_t length = (size_t)(replacement_end - replacement_start);
1184  rule->impl->replacement = rcutils_strndup(
1185  replacement_start, length, rule->impl->allocator);
1186  if (NULL == rule->impl->replacement) {
1187  RCL_SET_ERROR_MSG("failed to copy replacement");
1188  return RCL_RET_BAD_ALLOC;
1189  }
1190 
1191  return RCL_RET_OK;
1192 }
1193 
1195 
1198 RCL_LOCAL
1199 rcl_ret_t
1200 _rcl_parse_resource_match_token(rcl_lexer_lookahead2_t * lex_lookahead)
1201 {
1202  rcl_ret_t ret;
1203  rcl_lexeme_t lexeme;
1204 
1205  // Check arguments sanity
1206  assert(NULL != lex_lookahead);
1207 
1208  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1209  if (RCL_RET_OK != ret) {
1210  return ret;
1211  }
1212 
1213  if (RCL_LEXEME_TOKEN == lexeme) {
1214  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1215  } else if (RCL_LEXEME_WILD_ONE == lexeme) {
1216  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1217  return RCL_RET_ERROR;
1218  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1219  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1220  return RCL_RET_ERROR;
1221  } else {
1222  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1223  ret = RCL_RET_WRONG_LEXEME;
1224  }
1225 
1226  return ret;
1227 }
1228 
1230 
1233 RCL_LOCAL
1234 rcl_ret_t
1235 _rcl_parse_resource_match(
1236  rcl_lexer_lookahead2_t * lex_lookahead,
1237  rcl_allocator_t allocator,
1238  char ** resource_match)
1239 {
1240  rcl_ret_t ret;
1241  rcl_lexeme_t lexeme;
1242 
1243  // Check arguments sanity
1244  assert(NULL != lex_lookahead);
1245  assert(rcutils_allocator_is_valid(&allocator));
1246  assert(NULL != resource_match);
1247  assert(NULL == *resource_match);
1248 
1249  const char * match_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1250  if (NULL == match_start) {
1251  RCL_SET_ERROR_MSG("failed to get start of match");
1252  return RCL_RET_ERROR;
1253  }
1254 
1255  // private name (~/...) or fully qualified name (/...) ?
1256  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1257  if (RCL_RET_OK != ret) {
1258  return ret;
1259  }
1260  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1261  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1262  if (RCL_RET_OK != ret) {
1263  return ret;
1264  }
1265  }
1266 
1267  // token ( '/' token )*
1268  ret = _rcl_parse_resource_match_token(lex_lookahead);
1269  if (RCL_RET_OK != ret) {
1270  return ret;
1271  }
1272  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1273  if (RCL_RET_OK != ret) {
1274  return ret;
1275  }
1276  while (RCL_LEXEME_SEPARATOR != lexeme) {
1277  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1278  if (RCL_RET_WRONG_LEXEME == ret) {
1280  }
1281  ret = _rcl_parse_resource_match_token(lex_lookahead);
1282  if (RCL_RET_OK != ret) {
1283  return ret;
1284  }
1285  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1286  if (RCL_RET_OK != ret) {
1287  return ret;
1288  }
1289  }
1290 
1291  // Copy match into rule
1292  const char * match_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1293  const size_t length = (size_t)(match_end - match_start);
1294  *resource_match = rcutils_strndup(match_start, length, allocator);
1295  if (NULL == *resource_match) {
1296  RCL_SET_ERROR_MSG("failed to copy match");
1297  return RCL_RET_BAD_ALLOC;
1298  }
1299 
1300  return RCL_RET_OK;
1301 }
1302 
1303 RCL_LOCAL
1304 rcl_ret_t
1305 _rcl_parse_param_name_token(rcl_lexer_lookahead2_t * lex_lookahead)
1306 {
1307  rcl_ret_t ret;
1308  rcl_lexeme_t lexeme;
1309 
1310  // Check arguments sanity
1311  assert(NULL != lex_lookahead);
1312 
1313  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1314  if (RCL_RET_OK != ret) {
1315  return ret;
1316  }
1317  if (RCL_LEXEME_TOKEN != lexeme && RCL_LEXEME_FORWARD_SLASH != lexeme) {
1318  if (RCL_LEXEME_WILD_ONE == lexeme) {
1319  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1320  return RCL_RET_ERROR;
1321  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1322  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1323  return RCL_RET_ERROR;
1324  } else {
1325  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1326  return RCL_RET_WRONG_LEXEME;
1327  }
1328  }
1329  do {
1330  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1331  if (RCL_RET_OK != ret) {
1332  return ret;
1333  }
1334  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1335  if (RCL_RET_OK != ret) {
1336  return ret;
1337  }
1338  } while (RCL_LEXEME_TOKEN == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme);
1339  return RCL_RET_OK;
1340 }
1341 
1343 
1346 // TODO(hidmic): remove when parameter names are standardized to use slashes
1347 // in lieu of dots.
1348 RCL_LOCAL
1349 rcl_ret_t
1350 _rcl_parse_param_name(
1351  rcl_lexer_lookahead2_t * lex_lookahead,
1352  rcl_allocator_t allocator,
1353  char ** param_name)
1354 {
1355  rcl_ret_t ret;
1356  rcl_lexeme_t lexeme;
1357 
1358  // Check arguments sanity
1359  assert(NULL != lex_lookahead);
1360  assert(rcutils_allocator_is_valid(&allocator));
1361  assert(NULL != param_name);
1362  assert(NULL == *param_name);
1363 
1364  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1365  if (NULL == name_start) {
1366  RCL_SET_ERROR_MSG("failed to get start of param name");
1367  return RCL_RET_ERROR;
1368  }
1369 
1370  // token ( '.' token )*
1371  ret = _rcl_parse_param_name_token(lex_lookahead);
1372  if (RCL_RET_OK != ret) {
1373  return ret;
1374  }
1375  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1376  if (RCL_RET_OK != ret) {
1377  return ret;
1378  }
1379  while (RCL_LEXEME_SEPARATOR != lexeme) {
1380  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_DOT, NULL, NULL);
1381  if (RCL_RET_WRONG_LEXEME == ret) {
1383  }
1384  ret = _rcl_parse_param_name_token(lex_lookahead);
1385  if (RCL_RET_OK != ret) {
1386  return ret;
1387  }
1388  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1389  if (RCL_RET_OK != ret) {
1390  return ret;
1391  }
1392  }
1393 
1394  // Copy param name
1395  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1396  const size_t length = (size_t)(name_end - name_start);
1397  *param_name = rcutils_strndup(name_start, length, allocator);
1398  if (NULL == *param_name) {
1399  RCL_SET_ERROR_MSG("failed to copy param name");
1400  return RCL_RET_BAD_ALLOC;
1401  }
1402 
1403  return RCL_RET_OK;
1404 }
1405 
1406 
1408 
1411 RCL_LOCAL
1412 rcl_ret_t
1413 _rcl_parse_remap_match_name(
1414  rcl_lexer_lookahead2_t * lex_lookahead,
1415  rcl_remap_t * rule)
1416 {
1417  rcl_ret_t ret;
1418  rcl_lexeme_t lexeme;
1419 
1420  // Check arguments sanity
1421  assert(NULL != lex_lookahead);
1422  assert(NULL != rule);
1423 
1424  // rostopic:// rosservice://
1425  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1426  if (RCL_RET_OK != ret) {
1427  return ret;
1428  }
1429  if (RCL_LEXEME_URL_SERVICE == lexeme) {
1430  rule->impl->type = RCL_SERVICE_REMAP;
1431  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1432  } else if (RCL_LEXEME_URL_TOPIC == lexeme) {
1433  rule->impl->type = RCL_TOPIC_REMAP;
1434  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1435  } else {
1436  rule->impl->type = (RCL_TOPIC_REMAP | RCL_SERVICE_REMAP);
1437  }
1438  if (RCL_RET_OK != ret) {
1439  return ret;
1440  }
1441 
1442  ret = _rcl_parse_resource_match(
1443  lex_lookahead, rule->impl->allocator, &rule->impl->match);
1444  if (RCL_RET_WRONG_LEXEME == ret) {
1446  }
1447  return ret;
1448 }
1449 
1451 
1454 RCL_LOCAL
1455 rcl_ret_t
1456 _rcl_parse_remap_name_remap(
1457  rcl_lexer_lookahead2_t * lex_lookahead,
1458  rcl_remap_t * rule)
1459 {
1460  rcl_ret_t ret;
1461 
1462  // Check arguments sanity
1463  assert(NULL != lex_lookahead);
1464  assert(NULL != rule);
1465 
1466  // match
1467  ret = _rcl_parse_remap_match_name(lex_lookahead, rule);
1468  if (RCL_RET_OK != ret) {
1469  return ret;
1470  }
1471  // :=
1472  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1473  if (RCL_RET_WRONG_LEXEME == ret) {
1475  }
1476  // replacement
1477  ret = _rcl_parse_remap_replacement_name(lex_lookahead, rule);
1478  if (RCL_RET_OK != ret) {
1479  return ret;
1480  }
1481 
1482  return RCL_RET_OK;
1483 }
1484 
1486 
1489 RCL_LOCAL
1490 rcl_ret_t
1491 _rcl_parse_remap_namespace_replacement(
1492  rcl_lexer_lookahead2_t * lex_lookahead,
1493  rcl_remap_t * rule)
1494 {
1495  rcl_ret_t ret;
1496 
1497  // Check arguments sanity
1498  assert(NULL != lex_lookahead);
1499  assert(NULL != rule);
1500 
1501  // __ns
1502  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NS, NULL, NULL);
1503  if (RCL_RET_WRONG_LEXEME == ret) {
1505  }
1506  // :=
1507  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1508  if (RCL_RET_WRONG_LEXEME == ret) {
1510  }
1511  // /foo/bar
1512  const char * ns_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1513  if (NULL == ns_start) {
1514  RCL_SET_ERROR_MSG("failed to get start of namespace");
1515  return RCL_RET_ERROR;
1516  }
1517  ret = _rcl_parse_remap_fully_qualified_namespace(lex_lookahead);
1518  if (RCL_RET_OK != ret) {
1519  if (RCL_RET_INVALID_REMAP_RULE == ret) {
1520  // The name didn't start with a leading forward slash
1521  RCUTILS_LOG_WARN_NAMED(
1522  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1523  }
1524  return ret;
1525  }
1526  // There should be nothing left
1527  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1528  if (RCL_RET_OK != ret) {
1529  // The name must have started with a leading forward slash but had an otherwise invalid format
1530  RCUTILS_LOG_WARN_NAMED(
1531  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1532  return ret;
1533  }
1534 
1535  // Copy namespace into rule
1536  const char * ns_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1537  size_t length = (size_t)(ns_end - ns_start);
1538  rule->impl->replacement = rcutils_strndup(ns_start, length, rule->impl->allocator);
1539  if (NULL == rule->impl->replacement) {
1540  RCL_SET_ERROR_MSG("failed to copy namespace");
1541  return RCL_RET_BAD_ALLOC;
1542  }
1543 
1544  rule->impl->type = RCL_NAMESPACE_REMAP;
1545  return RCL_RET_OK;
1546 }
1547 
1549 
1552 RCL_LOCAL
1553 rcl_ret_t
1554 _rcl_parse_remap_nodename_replacement(
1555  rcl_lexer_lookahead2_t * lex_lookahead,
1556  rcl_remap_t * rule)
1557 {
1558  rcl_ret_t ret;
1559  const char * node_name;
1560  size_t length;
1561 
1562  // Check arguments sanity
1563  assert(NULL != lex_lookahead);
1564  assert(NULL != rule);
1565 
1566  // __node
1567  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NODE, NULL, NULL);
1568  if (RCL_RET_WRONG_LEXEME == ret) {
1570  }
1571  // :=
1572  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1573  if (RCL_RET_WRONG_LEXEME == ret) {
1575  }
1576  // new_node_name
1577  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &node_name, &length);
1578  if (RCL_RET_WRONG_LEXEME == ret) {
1579  node_name = rcl_lexer_lookahead2_get_text(lex_lookahead);
1580  RCUTILS_LOG_WARN_NAMED(
1581  ROS_PACKAGE_NAME, "Node name not remapped to invalid name: '%s'", node_name);
1583  }
1584  if (RCL_RET_OK != ret) {
1585  return ret;
1586  }
1587  // copy the node name into the replacement side of the rule
1588  rule->impl->replacement = rcutils_strndup(node_name, length, rule->impl->allocator);
1589  if (NULL == rule->impl->replacement) {
1590  RCL_SET_ERROR_MSG("failed to allocate node name");
1591  return RCL_RET_BAD_ALLOC;
1592  }
1593 
1594  rule->impl->type = RCL_NODENAME_REMAP;
1595  return RCL_RET_OK;
1596 }
1597 
1599 RCL_LOCAL
1600 rcl_ret_t
1601 _rcl_parse_nodename_prefix(
1602  rcl_lexer_lookahead2_t * lex_lookahead,
1603  rcl_allocator_t allocator,
1604  char ** node_name)
1605 {
1606  size_t length = 0;
1607  const char * token = NULL;
1608 
1609  // Check arguments sanity
1610  assert(NULL != lex_lookahead);
1611  assert(rcutils_allocator_is_valid(&allocator));
1612  assert(NULL != node_name);
1613  assert(NULL == *node_name);
1614 
1615  // Expect a token and a colon
1616  rcl_ret_t ret =
1617  rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &token, &length);
1618  if (RCL_RET_OK != ret) {
1619  return ret;
1620  }
1621  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_COLON, NULL, NULL);
1622  if (RCL_RET_OK != ret) {
1623  return ret;
1624  }
1625 
1626  // Copy the node name
1627  *node_name = rcutils_strndup(token, length, allocator);
1628  if (NULL == *node_name) {
1629  RCL_SET_ERROR_MSG("failed to allocate node name");
1630  return RCL_RET_BAD_ALLOC;
1631  }
1632 
1633  return RCL_RET_OK;
1634 }
1635 
1637 
1641 RCL_LOCAL
1642 rcl_ret_t
1643 _rcl_parse_remap_nodename_prefix(
1644  rcl_lexer_lookahead2_t * lex_lookahead,
1645  rcl_remap_t * rule)
1646 {
1647  // Check arguments sanity
1648  assert(NULL != lex_lookahead);
1649  assert(NULL != rule);
1650 
1651  rcl_ret_t ret = _rcl_parse_nodename_prefix(
1652  lex_lookahead, rule->impl->allocator, &rule->impl->node_name);
1653  if (RCL_RET_WRONG_LEXEME == ret) {
1655  }
1656  return ret;
1657 }
1658 
1660 
1668 RCL_LOCAL
1669 rcl_ret_t
1670 _rcl_parse_remap_begin_remap_rule(
1671  rcl_lexer_lookahead2_t * lex_lookahead,
1672  rcl_remap_t * rule)
1673 {
1674  rcl_ret_t ret;
1675  rcl_lexeme_t lexeme1;
1676  rcl_lexeme_t lexeme2;
1677 
1678  // Check arguments sanity
1679  assert(NULL != lex_lookahead);
1680  assert(NULL != rule);
1681 
1682  // Check for optional nodename prefix
1683  ret = rcl_lexer_lookahead2_peek2(lex_lookahead, &lexeme1, &lexeme2);
1684  if (RCL_RET_OK != ret) {
1685  return ret;
1686  }
1687  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1688  ret = _rcl_parse_remap_nodename_prefix(lex_lookahead, rule);
1689  if (RCL_RET_OK != ret) {
1690  return ret;
1691  }
1692  }
1693 
1694  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme1);
1695  if (RCL_RET_OK != ret) {
1696  return ret;
1697  }
1698 
1699  // What type of rule is this (node name replacement, namespace replacement, or name remap)?
1700  if (RCL_LEXEME_NODE == lexeme1) {
1701  ret = _rcl_parse_remap_nodename_replacement(lex_lookahead, rule);
1702  if (RCL_RET_OK != ret) {
1703  return ret;
1704  }
1705  } else if (RCL_LEXEME_NS == lexeme1) {
1706  ret = _rcl_parse_remap_namespace_replacement(lex_lookahead, rule);
1707  if (RCL_RET_OK != ret) {
1708  return ret;
1709  }
1710  } else {
1711  ret = _rcl_parse_remap_name_remap(lex_lookahead, rule);
1712  if (RCL_RET_OK != ret) {
1713  return ret;
1714  }
1715  }
1716 
1717  // Make sure all characters in string have been consumed
1718  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1719  if (RCL_RET_WRONG_LEXEME == ret) {
1721  }
1722  return ret;
1723 }
1724 
1725 RCL_LOCAL
1726 rcl_ret_t
1727 _rcl_parse_log_level_name(
1728  rcl_lexer_lookahead2_t * lex_lookahead,
1729  rcl_allocator_t * allocator,
1730  char ** logger_name)
1731 {
1732  rcl_lexeme_t lexeme;
1733 
1734  // Check arguments sanity
1735  assert(NULL != lex_lookahead);
1736  assert(rcutils_allocator_is_valid(allocator));
1737  assert(NULL != logger_name);
1738  assert(NULL == *logger_name);
1739 
1740  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1741  if (NULL == name_start) {
1742  RCL_SET_ERROR_MSG("failed to get start of logger name");
1743  return RCL_RET_ERROR;
1744  }
1745 
1746  rcl_ret_t ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1747  if (RCL_RET_OK != ret) {
1748  return ret;
1749  }
1750 
1751  while (RCL_LEXEME_SEPARATOR != lexeme) {
1752  ret = rcl_lexer_lookahead2_expect(lex_lookahead, lexeme, NULL, NULL);
1753  if (RCL_RET_OK != ret) {
1754  return ret;
1755  }
1756 
1757  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1758  if (RCL_RET_OK != ret) {
1759  return ret;
1760  }
1761 
1762  if (lexeme == RCL_LEXEME_EOF) {
1764  return ret;
1765  }
1766  }
1767 
1768  // Copy logger name
1769  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1770  const size_t length = (size_t)(name_end - name_start);
1771  *logger_name = rcutils_strndup(name_start, length, *allocator);
1772  if (NULL == *logger_name) {
1773  RCL_SET_ERROR_MSG("failed to copy logger name");
1774  return RCL_RET_BAD_ALLOC;
1775  }
1776 
1777  return RCL_RET_OK;
1778 }
1779 
1780 rcl_ret_t
1781 _rcl_parse_log_level(
1782  const char * arg,
1783  rcl_log_levels_t * log_levels)
1784 {
1785  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1786  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
1787  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels->logger_settings, RCL_RET_INVALID_ARGUMENT);
1788  rcl_allocator_t * allocator = &log_levels->allocator;
1789  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
1790 
1791  rcl_ret_t ret = RCL_RET_OK;
1792  char * logger_name = NULL;
1793  int level = 0;
1794  rcutils_ret_t rcutils_ret = RCUTILS_RET_OK;
1795 
1797 
1798  ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, *allocator);
1799  if (RCL_RET_OK != ret) {
1800  return ret;
1801  }
1802 
1803  ret = _rcl_parse_log_level_name(&lex_lookahead, allocator, &logger_name);
1804  if (RCL_RET_OK == ret) {
1805  if (strlen(logger_name) == 0) {
1806  RCL_SET_ERROR_MSG("Argument has an invalid logger item that name is empty");
1808  goto cleanup;
1809  }
1810 
1811  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1812  if (RCL_RET_WRONG_LEXEME == ret) {
1814  goto cleanup;
1815  }
1816 
1817  const char * level_token;
1818  size_t level_token_length;
1820  &lex_lookahead, RCL_LEXEME_TOKEN, &level_token, &level_token_length);
1821  if (RCL_RET_WRONG_LEXEME == ret) {
1823  goto cleanup;
1824  }
1825 
1826  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1827  if (RCL_RET_OK != ret) {
1829  goto cleanup;
1830  }
1831 
1832  rcutils_ret = rcutils_logging_severity_level_from_string(
1833  level_token, *allocator, &level);
1834  if (RCUTILS_RET_OK == rcutils_ret) {
1836  log_levels, logger_name, (rcl_log_severity_t)level);
1837  if (ret != RCL_RET_OK) {
1838  goto cleanup;
1839  }
1840  }
1841  } else {
1842  rcutils_ret = rcutils_logging_severity_level_from_string(
1843  arg, *allocator, &level);
1844  if (RCUTILS_RET_OK == rcutils_ret) {
1845  if (log_levels->default_logger_level != (rcl_log_severity_t)level) {
1846  if (log_levels->default_logger_level != RCUTILS_LOG_SEVERITY_UNSET) {
1847  RCUTILS_LOG_DEBUG_NAMED(
1848  ROS_PACKAGE_NAME, "Minimum default log level will be replaced from %d to %d",
1849  log_levels->default_logger_level, level);
1850  }
1851  log_levels->default_logger_level = (rcl_log_severity_t)level;
1852  }
1853  ret = RCL_RET_OK;
1854  }
1855  }
1856 
1857  if (RCUTILS_RET_OK != rcutils_ret) {
1858  RCL_SET_ERROR_MSG("Argument does not use a valid severity level");
1859  ret = RCL_RET_ERROR;
1860  }
1861 
1862 cleanup:
1863  if (logger_name) {
1864  allocator->deallocate(logger_name, allocator->state);
1865  }
1866  rcl_ret_t rv = rcl_lexer_lookahead2_fini(&lex_lookahead);
1867  if (RCL_RET_OK != rv) {
1868  if (RCL_RET_OK != ret) {
1869  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1870  } else {
1871  ret = rv;
1872  }
1873  }
1874 
1875  return ret;
1876 }
1877 
1878 rcl_ret_t
1879 _rcl_parse_remap_rule(
1880  const char * arg,
1881  rcl_allocator_t allocator,
1882  rcl_remap_t * output_rule)
1883 {
1884  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1885  RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT);
1886 
1887  output_rule->impl =
1888  allocator.allocate(sizeof(rcl_remap_impl_t), allocator.state);
1889  if (NULL == output_rule->impl) {
1890  return RCL_RET_BAD_ALLOC;
1891  }
1892  output_rule->impl->allocator = allocator;
1893  output_rule->impl->type = RCL_UNKNOWN_REMAP;
1894  output_rule->impl->node_name = NULL;
1895  output_rule->impl->match = NULL;
1896  output_rule->impl->replacement = NULL;
1897 
1899  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, allocator);
1900 
1901  if (RCL_RET_OK == ret) {
1902  ret = _rcl_parse_remap_begin_remap_rule(&lex_lookahead, output_rule);
1903 
1904  rcl_ret_t fini_ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
1905  if (RCL_RET_OK != ret) {
1906  if (RCL_RET_OK != fini_ret) {
1907  RCUTILS_LOG_ERROR_NAMED(
1908  ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1909  }
1910  } else {
1911  if (RCL_RET_OK == fini_ret) {
1912  return RCL_RET_OK;
1913  }
1914  ret = fini_ret;
1915  }
1916  }
1917 
1918  // cleanup output rule but keep first error return code
1919  if (RCL_RET_OK != rcl_remap_fini(output_rule)) {
1920  RCUTILS_LOG_ERROR_NAMED(
1921  ROS_PACKAGE_NAME, "Failed to fini remap rule after error occurred");
1922  }
1923 
1924  return ret;
1925 }
1926 
1927 rcl_ret_t
1928 _rcl_parse_param_rule(
1929  const char * arg,
1930  rcl_params_t * params)
1931 {
1932  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1933  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
1934 
1936 
1937  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, params->allocator);
1938  if (RCL_RET_OK != ret) {
1939  return ret;
1940  }
1941 
1942  rcl_lexeme_t lexeme1;
1943  rcl_lexeme_t lexeme2;
1944  char * node_name = NULL;
1945  char * param_name = NULL;
1946 
1947  // Check for optional nodename prefix
1948  ret = rcl_lexer_lookahead2_peek2(&lex_lookahead, &lexeme1, &lexeme2);
1949  if (RCL_RET_OK != ret) {
1950  goto cleanup;
1951  }
1952 
1953  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1954  ret = _rcl_parse_nodename_prefix(&lex_lookahead, params->allocator, &node_name);
1955  if (RCL_RET_OK != ret) {
1956  if (RCL_RET_WRONG_LEXEME == ret) {
1958  }
1959  goto cleanup;
1960  }
1961  } else {
1962  node_name = rcutils_strdup("/**", params->allocator);
1963  if (NULL == node_name) {
1964  ret = RCL_RET_BAD_ALLOC;
1965  goto cleanup;
1966  }
1967  }
1968 
1969  // TODO(hidmic): switch to _rcl_parse_resource_match() when parameter names
1970  // are standardized to use slashes in lieu of dots.
1971  ret = _rcl_parse_param_name(&lex_lookahead, params->allocator, &param_name);
1972  if (RCL_RET_OK != ret) {
1973  if (RCL_RET_WRONG_LEXEME == ret) {
1975  }
1976  goto cleanup;
1977  }
1978 
1979  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1980  if (RCL_RET_WRONG_LEXEME == ret) {
1982  goto cleanup;
1983  }
1984 
1985  const char * yaml_value = rcl_lexer_lookahead2_get_text(&lex_lookahead);
1986  if (!rcl_parse_yaml_value(node_name, param_name, yaml_value, params)) {
1988  goto cleanup;
1989  }
1990 
1991 cleanup:
1992  params->allocator.deallocate(param_name, params->allocator.state);
1993  params->allocator.deallocate(node_name, params->allocator.state);
1994  if (RCL_RET_OK != ret) {
1995  if (RCL_RET_OK != rcl_lexer_lookahead2_fini(&lex_lookahead)) {
1996  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1997  }
1998  } else {
1999  ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
2000  }
2001  return ret;
2002 }
2003 
2004 rcl_ret_t
2005 _rcl_parse_param_file(
2006  const char * arg,
2007  rcl_allocator_t allocator,
2008  rcl_params_t * params,
2009  char ** param_file)
2010 {
2011  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2012  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
2013  RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT);
2014  *param_file = rcutils_strdup(arg, allocator);
2015  if (NULL == *param_file) {
2016  RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path");
2017  return RCL_RET_BAD_ALLOC;
2018  }
2019  if (!rcl_parse_yaml_file(*param_file, params)) {
2020  allocator.deallocate(*param_file, allocator.state);
2021  *param_file = NULL;
2022  // Error message already set.
2023  return RCL_RET_ERROR;
2024  }
2025  return RCL_RET_OK;
2026 }
2027 
2028 rcl_ret_t
2029 _rcl_parse_external_log_file_name(
2030  const char * arg,
2031  rcl_allocator_t allocator,
2032  char ** log_file_name_prefix)
2033 {
2034  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2035  RCL_CHECK_ARGUMENT_FOR_NULL(log_file_name_prefix, RCL_RET_INVALID_ARGUMENT);
2036 
2037  *log_file_name_prefix = rcutils_strdup(arg, allocator);
2038  if (NULL == *log_file_name_prefix) {
2039  RCL_SET_ERROR_MSG("Failed to allocate memory for external log file name prefix");
2040  return RCL_RET_BAD_ALLOC;
2041  }
2042  return RCL_RET_OK;
2043 }
2044 
2045 rcl_ret_t
2046 _rcl_parse_external_log_config_file(
2047  const char * arg,
2048  rcl_allocator_t allocator,
2049  char ** log_config_file)
2050 {
2051  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2052  RCL_CHECK_ARGUMENT_FOR_NULL(log_config_file, RCL_RET_INVALID_ARGUMENT);
2053 
2054  *log_config_file = rcutils_strdup(arg, allocator);
2055  // TODO(hidmic): add file checks
2056  if (NULL == *log_config_file) {
2057  RCL_SET_ERROR_MSG("Failed to allocate memory for external log config file");
2058  return RCL_RET_BAD_ALLOC;
2059  }
2060  return RCL_RET_OK;
2061 }
2062 
2063 rcl_ret_t
2064 _rcl_parse_enclave(
2065  const char * arg,
2066  rcl_allocator_t allocator,
2067  char ** enclave)
2068 {
2069  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2070  RCL_CHECK_ARGUMENT_FOR_NULL(enclave, RCL_RET_INVALID_ARGUMENT);
2071 
2072  *enclave = rcutils_strdup(arg, allocator);
2073  if (NULL == *enclave) {
2074  RCL_SET_ERROR_MSG("Failed to allocate memory for enclave name");
2075  return RCL_RET_BAD_ALLOC;
2076  }
2077  return RCL_RET_OK;
2078 }
2079 
2080 rcl_ret_t
2081 _rcl_parse_disabling_flag(
2082  const char * arg,
2083  const char * suffix,
2084  bool * disable)
2085 {
2086  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2087  RCL_CHECK_ARGUMENT_FOR_NULL(suffix, RCL_RET_INVALID_ARGUMENT);
2088  RCL_CHECK_ARGUMENT_FOR_NULL(disable, RCL_RET_INVALID_ARGUMENT);
2089 
2090  const size_t enable_prefix_len = strlen(RCL_ENABLE_FLAG_PREFIX);
2091  if (
2092  strncmp(RCL_ENABLE_FLAG_PREFIX, arg, enable_prefix_len) == 0 &&
2093  strcmp(suffix, arg + enable_prefix_len) == 0)
2094  {
2095  *disable = false;
2096  return RCL_RET_OK;
2097  }
2098 
2099  const size_t disable_prefix_len = strlen(RCL_DISABLE_FLAG_PREFIX);
2100  if (
2101  strncmp(RCL_DISABLE_FLAG_PREFIX, arg, disable_prefix_len) == 0 &&
2102  strcmp(suffix, arg + disable_prefix_len) == 0)
2103  {
2104  *disable = true;
2105  return RCL_RET_OK;
2106  }
2107 
2108  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
2109  "Argument is not a %s%s nor a %s%s flag.",
2110  RCL_ENABLE_FLAG_PREFIX, suffix,
2111  RCL_DISABLE_FLAG_PREFIX, suffix);
2112  return RCL_RET_ERROR;
2113 }
2114 
2115 rcl_ret_t
2116 _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator)
2117 {
2118  args->impl = allocator->allocate(sizeof(rcl_arguments_impl_t), allocator->state);
2119  if (NULL == args->impl) {
2120  return RCL_RET_BAD_ALLOC;
2121  }
2122 
2123  rcl_arguments_impl_t * args_impl = args->impl;
2124  args_impl->num_remap_rules = 0;
2125  args_impl->remap_rules = NULL;
2127  args_impl->external_log_file_name_prefix = NULL;
2128  args_impl->external_log_config_file = NULL;
2129  args_impl->unparsed_args = NULL;
2130  args_impl->num_unparsed_args = 0;
2131  args_impl->unparsed_ros_args = NULL;
2132  args_impl->num_unparsed_ros_args = 0;
2133  args_impl->parameter_overrides = NULL;
2134  args_impl->parameter_files = NULL;
2135  args_impl->num_param_files_args = 0;
2136  args_impl->log_stdout_disabled = false;
2137  args_impl->log_rosout_disabled = false;
2138  args_impl->log_ext_lib_disabled = false;
2139  args_impl->enclave = NULL;
2140  args_impl->allocator = *allocator;
2141 
2142  return RCL_RET_OK;
2143 }
2144 
#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:83
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.
#define RCL_EXTERNAL_LOG_FILE_NAME_PREFIX
The ROS log file name prefix to configure external logging.
Definition: arguments.h:72
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:87
#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:79
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:75
#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(void)
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_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_log_levels_t rcl_get_zero_initialized_log_levels(void)
Return a rcl_log_levels_t struct with members initialized to zero value.
Definition: log_level.c:23
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 * external_log_file_name_prefix
A prefix used to external log file name.
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:115
#define RCL_RET_INVALID_PARAM_RULE
Argument is not a valid parameter rule.
Definition: types.h:113
#define RCL_RET_WRONG_LEXEME
Expected one type of lexeme but got another.
Definition: types.h:109
#define RCL_RET_INVALID_ROS_ARGS
Found invalid ros argument while parsing.
Definition: types.h:111
#define RCL_RET_INVALID_REMAP_RULE
Argument is not a valid remap rule.
Definition: types.h:107
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#define RCL_RET_BAD_ALLOC
Failed to allocate memory return code.
Definition: types.h:33
#define RCL_RET_INVALID_ARGUMENT
Invalid argument return code.
Definition: types.h:35
#define RCL_RET_ERROR
Unspecified error return code.
Definition: types.h:29
rmw_ret_t rcl_ret_t
The type that holds an rcl return code.
Definition: types.h:24