ROS 2 rclcpp + rcl - rolling  rolling-e615c7c3
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  // All members are initialized to 0 or NULL by C99 6.7.8/10.
801  static rcl_arguments_t zero_arguments;
802  return zero_arguments;
803 }
804 
805 rcl_ret_t
807  const char * const * argv,
808  const rcl_arguments_t * args,
809  rcl_allocator_t allocator,
810  int * nonros_argc,
811  const char *** nonros_argv)
812 {
813  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
814  RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
815  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT);
816  RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argv, RCL_RET_INVALID_ARGUMENT);
817  if (NULL != *nonros_argv) {
818  RCL_SET_ERROR_MSG("Output nonros_argv pointer is not null. May leak memory.");
820  }
821 
822  *nonros_argc = rcl_arguments_get_count_unparsed(args);
823  if (*nonros_argc < 0) {
824  RCL_SET_ERROR_MSG("Failed to get unparsed non ROS specific arguments count.");
826  } else if (*nonros_argc > 0) {
827  RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
828  }
829 
830  *nonros_argv = NULL;
831  if (0 == *nonros_argc) {
832  return RCL_RET_OK;
833  }
834 
835  int * unparsed_indices = NULL;
836  rcl_ret_t ret = rcl_arguments_get_unparsed(args, allocator, &unparsed_indices);
837 
838  if (RCL_RET_OK != ret) {
839  return ret;
840  }
841 
842  size_t alloc_size = sizeof(char *) * *nonros_argc;
843  *nonros_argv = allocator.allocate(alloc_size, allocator.state);
844  if (NULL == *nonros_argv) {
845  allocator.deallocate(unparsed_indices, allocator.state);
846  return RCL_RET_BAD_ALLOC;
847  }
848  for (int i = 0; i < *nonros_argc; ++i) {
849  (*nonros_argv)[i] = argv[unparsed_indices[i]];
850  }
851 
852  allocator.deallocate(unparsed_indices, allocator.state);
853  return RCL_RET_OK;
854 }
855 
856 rcl_ret_t
858  const rcl_arguments_t * args,
859  rcl_arguments_t * args_out)
860 {
861  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);
862  RCUTILS_CAN_SET_MSG_AND_RETURN_WITH_ERROR_OF(RCL_RET_BAD_ALLOC);
863 
864  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
865  RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
866  RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
867  if (NULL != args_out->impl) {
868  RCL_SET_ERROR_MSG("args_out must be zero initialized");
870  }
871 
872  rcl_allocator_t allocator = args->impl->allocator;
873 
874  rcl_ret_t ret = _rcl_allocate_initialized_arguments_impl(args_out, &allocator);
875  if (RCL_RET_OK != ret) {
876  return ret;
877  }
878 
879  if (args->impl->num_unparsed_args) {
880  // Copy unparsed args
881  args_out->impl->unparsed_args = allocator.allocate(
882  sizeof(int) * args->impl->num_unparsed_args, allocator.state);
883  if (NULL == args_out->impl->unparsed_args) {
884  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
885  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
886  }
887  return RCL_RET_BAD_ALLOC;
888  }
889  for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
890  args_out->impl->unparsed_args[i] = args->impl->unparsed_args[i];
891  }
892  args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
893  }
894 
895  if (args->impl->num_unparsed_ros_args) {
896  // Copy unparsed ROS args
897  args_out->impl->unparsed_ros_args = allocator.allocate(
898  sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
899  if (NULL == args_out->impl->unparsed_ros_args) {
900  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
901  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
902  }
903  return RCL_RET_BAD_ALLOC;
904  }
905  for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
906  args_out->impl->unparsed_ros_args[i] = args->impl->unparsed_ros_args[i];
907  }
909  }
910 
911  if (args->impl->num_remap_rules) {
912  // Copy remap rules
913  args_out->impl->remap_rules = allocator.allocate(
914  sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state);
915  if (NULL == args_out->impl->remap_rules) {
916  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
917  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
918  }
919  return RCL_RET_BAD_ALLOC;
920  }
921  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
923  ret = rcl_remap_copy(
924  &(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i]));
925  if (RCL_RET_OK != ret) {
926  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
927  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
928  }
929  return ret;
930  }
931  ++(args_out->impl->num_remap_rules);
932  }
933  }
934 
935  // Copy parameter rules
936  if (args->impl->parameter_overrides) {
937  args_out->impl->parameter_overrides =
938  rcl_yaml_node_struct_copy(args->impl->parameter_overrides);
939  }
940 
941  // Copy parameter files
942  if (args->impl->num_param_files_args) {
943  args_out->impl->parameter_files = allocator.zero_allocate(
944  args->impl->num_param_files_args, sizeof(char *), allocator.state);
945  if (NULL == args_out->impl->parameter_files) {
946  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
947  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
948  }
949  return RCL_RET_BAD_ALLOC;
950  }
951  for (int i = 0; i < args->impl->num_param_files_args; ++i) {
952  args_out->impl->parameter_files[i] =
953  rcutils_strdup(args->impl->parameter_files[i], allocator);
954  if (NULL == args_out->impl->parameter_files[i]) {
955  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
956  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
957  }
958  return RCL_RET_BAD_ALLOC;
959  }
960  ++(args_out->impl->num_param_files_args);
961  }
962  }
963  char * enclave_copy = rcutils_strdup(args->impl->enclave, allocator);
964  if (args->impl->enclave && !enclave_copy) {
965  if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
966  RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
967  } else {
968  RCL_SET_ERROR_MSG("Error while copying enclave argument");
969  }
970  return RCL_RET_BAD_ALLOC;
971  }
972  args_out->impl->enclave = enclave_copy;
973  return RCL_RET_OK;
974 }
975 
976 rcl_ret_t
978  rcl_arguments_t * args)
979 {
980  RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
981  if (args->impl) {
982  rcl_ret_t ret = RCL_RET_OK;
983  if (args->impl->remap_rules) {
984  for (int i = 0; i < args->impl->num_remap_rules; ++i) {
985  rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i]));
986  if (remap_ret != RCL_RET_OK) {
987  ret = remap_ret;
988  RCUTILS_LOG_ERROR_NAMED(
989  ROS_PACKAGE_NAME,
990  "Failed to finalize remap rule while finalizing arguments. Continuing...");
991  }
992  }
993  args->impl->allocator.deallocate(args->impl->remap_rules, args->impl->allocator.state);
994  args->impl->remap_rules = NULL;
995  args->impl->num_remap_rules = 0;
996  }
997 
998  rcl_ret_t log_levels_ret = rcl_log_levels_fini(&args->impl->log_levels);
999  if (log_levels_ret != RCL_RET_OK) {
1000  ret = log_levels_ret;
1001  RCUTILS_LOG_ERROR_NAMED(
1002  ROS_PACKAGE_NAME,
1003  "Failed to finalize log levels while finalizing arguments. Continuing...");
1004  }
1005 
1006  args->impl->allocator.deallocate(args->impl->unparsed_args, args->impl->allocator.state);
1007  args->impl->num_unparsed_args = 0;
1008  args->impl->unparsed_args = NULL;
1009 
1010  args->impl->allocator.deallocate(args->impl->unparsed_ros_args, args->impl->allocator.state);
1011  args->impl->num_unparsed_ros_args = 0;
1012  args->impl->unparsed_ros_args = NULL;
1013 
1014  if (args->impl->parameter_overrides) {
1015  rcl_yaml_node_struct_fini(args->impl->parameter_overrides);
1016  args->impl->parameter_overrides = NULL;
1017  }
1018 
1019  if (args->impl->parameter_files) {
1020  for (int p = 0; p < args->impl->num_param_files_args; ++p) {
1021  args->impl->allocator.deallocate(
1022  args->impl->parameter_files[p], args->impl->allocator.state);
1023  }
1024  args->impl->allocator.deallocate(args->impl->parameter_files, args->impl->allocator.state);
1025  args->impl->num_param_files_args = 0;
1026  args->impl->parameter_files = NULL;
1027  }
1028  args->impl->allocator.deallocate(args->impl->enclave, args->impl->allocator.state);
1029 
1030  if (NULL != args->impl->external_log_file_name_prefix) {
1031  args->impl->allocator.deallocate(
1032  args->impl->external_log_file_name_prefix, args->impl->allocator.state);
1033  args->impl->external_log_file_name_prefix = NULL;
1034  }
1035 
1036  if (NULL != args->impl->external_log_config_file) {
1037  args->impl->allocator.deallocate(
1038  args->impl->external_log_config_file, args->impl->allocator.state);
1039  args->impl->external_log_config_file = NULL;
1040  }
1041 
1042  args->impl->allocator.deallocate(args->impl, args->impl->allocator.state);
1043  args->impl = NULL;
1044  return ret;
1045  }
1046  RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice");
1047  return RCL_RET_ERROR;
1048 }
1049 
1051 
1054 RCL_LOCAL
1055 rcl_ret_t
1056 _rcl_parse_remap_fully_qualified_namespace(
1057  rcl_lexer_lookahead2_t * lex_lookahead)
1058 {
1059  rcl_ret_t ret;
1060 
1061  // Check arguments sanity
1062  assert(NULL != lex_lookahead);
1063 
1064  // Must have at least one Forward slash /
1065  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1066  if (RCL_RET_WRONG_LEXEME == ret) {
1068  }
1069 
1070  // repeated tokens and slashes (allow trailing slash, but don't require it)
1071  while (true) {
1072  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, NULL, NULL);
1073  if (RCL_RET_WRONG_LEXEME == ret) {
1074  rcl_reset_error();
1075  break;
1076  }
1077  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1078  if (RCL_RET_WRONG_LEXEME == ret) {
1079  rcl_reset_error();
1080  break;
1081  }
1082  }
1083  return RCL_RET_OK;
1084 }
1085 
1087 
1090 RCL_LOCAL
1091 rcl_ret_t
1092 _rcl_parse_remap_replacement_token(rcl_lexer_lookahead2_t * lex_lookahead)
1093 {
1094  rcl_ret_t ret;
1095  rcl_lexeme_t lexeme;
1096 
1097  // Check arguments sanity
1098  assert(NULL != lex_lookahead);
1099 
1100  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1101  if (RCL_RET_OK != ret) {
1102  return ret;
1103  }
1104 
1105  if (
1106  RCL_LEXEME_BR1 == lexeme || RCL_LEXEME_BR2 == lexeme || RCL_LEXEME_BR3 == lexeme ||
1107  RCL_LEXEME_BR4 == lexeme || RCL_LEXEME_BR5 == lexeme || RCL_LEXEME_BR6 == lexeme ||
1108  RCL_LEXEME_BR7 == lexeme || RCL_LEXEME_BR8 == lexeme || RCL_LEXEME_BR9 == lexeme)
1109  {
1110  RCL_SET_ERROR_MSG("Backreferences are not implemented");
1111  return RCL_RET_ERROR;
1112  } else if (RCL_LEXEME_TOKEN == lexeme) {
1113  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1114  } else {
1116  }
1117 
1118  return ret;
1119 }
1120 
1122 
1125 RCL_LOCAL
1126 rcl_ret_t
1127 _rcl_parse_remap_replacement_name(
1128  rcl_lexer_lookahead2_t * lex_lookahead,
1129  rcl_remap_t * rule)
1130 {
1131  rcl_ret_t ret;
1132  rcl_lexeme_t lexeme;
1133 
1134  // Check arguments sanity
1135  assert(NULL != lex_lookahead);
1136  assert(NULL != rule);
1137 
1138  const char * replacement_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1139  if (NULL == replacement_start) {
1140  RCL_SET_ERROR_MSG("failed to get start of replacement");
1141  return RCL_RET_ERROR;
1142  }
1143 
1144  // private name (~/...) or fully qualified name (/...) ?
1145  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1146  if (RCL_RET_OK != ret) {
1147  return ret;
1148  }
1149  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1150  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1151  }
1152  if (RCL_RET_OK != ret) {
1153  return ret;
1154  }
1155 
1156  // token ( '/' token )*
1157  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1158  if (RCL_RET_OK != ret) {
1159  return ret;
1160  }
1161  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1162  if (RCL_RET_OK != ret) {
1163  return ret;
1164  }
1165  while (RCL_LEXEME_EOF != lexeme) {
1166  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1167  if (RCL_RET_WRONG_LEXEME == ret) {
1169  }
1170  ret = _rcl_parse_remap_replacement_token(lex_lookahead);
1171  if (RCL_RET_OK != ret) {
1172  return ret;
1173  }
1174  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1175  if (RCL_RET_OK != ret) {
1176  return ret;
1177  }
1178  }
1179 
1180  // Copy replacement into rule
1181  const char * replacement_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1182  size_t length = (size_t)(replacement_end - replacement_start);
1183  rule->impl->replacement = rcutils_strndup(
1184  replacement_start, length, rule->impl->allocator);
1185  if (NULL == rule->impl->replacement) {
1186  RCL_SET_ERROR_MSG("failed to copy replacement");
1187  return RCL_RET_BAD_ALLOC;
1188  }
1189 
1190  return RCL_RET_OK;
1191 }
1192 
1194 
1197 RCL_LOCAL
1198 rcl_ret_t
1199 _rcl_parse_resource_match_token(rcl_lexer_lookahead2_t * lex_lookahead)
1200 {
1201  rcl_ret_t ret;
1202  rcl_lexeme_t lexeme;
1203 
1204  // Check arguments sanity
1205  assert(NULL != lex_lookahead);
1206 
1207  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1208  if (RCL_RET_OK != ret) {
1209  return ret;
1210  }
1211 
1212  if (RCL_LEXEME_TOKEN == lexeme) {
1213  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1214  } else if (RCL_LEXEME_WILD_ONE == lexeme) {
1215  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1216  ret = RCL_RET_ERROR;
1217  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1218  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1219  ret = RCL_RET_ERROR;
1220  } else {
1221  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1222  ret = RCL_RET_WRONG_LEXEME;
1223  }
1224 
1225  return ret;
1226 }
1227 
1229 
1232 RCL_LOCAL
1233 rcl_ret_t
1234 _rcl_parse_resource_match(
1235  rcl_lexer_lookahead2_t * lex_lookahead,
1236  rcl_allocator_t allocator,
1237  char ** resource_match)
1238 {
1239  rcl_ret_t ret;
1240  rcl_lexeme_t lexeme;
1241 
1242  // Check arguments sanity
1243  assert(NULL != lex_lookahead);
1244  assert(rcutils_allocator_is_valid(&allocator));
1245  assert(NULL != resource_match);
1246  assert(NULL == *resource_match);
1247 
1248  const char * match_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1249  if (NULL == match_start) {
1250  RCL_SET_ERROR_MSG("failed to get start of match");
1251  return RCL_RET_ERROR;
1252  }
1253 
1254  // private name (~/...) or fully qualified name (/...) ?
1255  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1256  if (RCL_RET_OK != ret) {
1257  return ret;
1258  }
1259  if (RCL_LEXEME_TILDE_SLASH == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme) {
1260  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1261  if (RCL_RET_OK != ret) {
1262  return ret;
1263  }
1264  }
1265 
1266  // token ( '/' token )*
1267  ret = _rcl_parse_resource_match_token(lex_lookahead);
1268  if (RCL_RET_OK != ret) {
1269  return ret;
1270  }
1271  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1272  if (RCL_RET_OK != ret) {
1273  return ret;
1274  }
1275  while (RCL_LEXEME_SEPARATOR != lexeme) {
1276  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_FORWARD_SLASH, NULL, NULL);
1277  if (RCL_RET_WRONG_LEXEME == ret) {
1279  } else if (RCL_RET_OK != ret) {
1280  // Another failure
1281  return ret;
1282  }
1283  ret = _rcl_parse_resource_match_token(lex_lookahead);
1284  if (RCL_RET_OK != ret) {
1285  return ret;
1286  }
1287  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1288  if (RCL_RET_OK != ret) {
1289  return ret;
1290  }
1291  }
1292 
1293  // Copy match into rule
1294  const char * match_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1295  const size_t length = (size_t)(match_end - match_start);
1296  *resource_match = rcutils_strndup(match_start, length, allocator);
1297  if (NULL == *resource_match) {
1298  RCL_SET_ERROR_MSG("failed to copy match");
1299  return RCL_RET_BAD_ALLOC;
1300  }
1301 
1302  return RCL_RET_OK;
1303 }
1304 
1305 RCL_LOCAL
1306 rcl_ret_t
1307 _rcl_parse_param_name_token(rcl_lexer_lookahead2_t * lex_lookahead)
1308 {
1309  rcl_ret_t ret;
1310  rcl_lexeme_t lexeme;
1311 
1312  // Check arguments sanity
1313  assert(NULL != lex_lookahead);
1314 
1315  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1316  if (RCL_RET_OK != ret) {
1317  return ret;
1318  }
1319  if (RCL_LEXEME_TOKEN != lexeme && RCL_LEXEME_FORWARD_SLASH != lexeme) {
1320  if (RCL_LEXEME_WILD_ONE == lexeme) {
1321  RCL_SET_ERROR_MSG("Wildcard '*' is not implemented");
1322  return RCL_RET_ERROR;
1323  } else if (RCL_LEXEME_WILD_MULTI == lexeme) {
1324  RCL_SET_ERROR_MSG("Wildcard '**' is not implemented");
1325  return RCL_RET_ERROR;
1326  } else {
1327  RCL_SET_ERROR_MSG("Expecting token or wildcard");
1328  return RCL_RET_WRONG_LEXEME;
1329  }
1330  }
1331  do {
1332  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
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  } while (RCL_LEXEME_TOKEN == lexeme || RCL_LEXEME_FORWARD_SLASH == lexeme);
1341  return RCL_RET_OK;
1342 }
1343 
1345 
1348 // TODO(hidmic): remove when parameter names are standardized to use slashes
1349 // in lieu of dots.
1350 RCL_LOCAL
1351 rcl_ret_t
1352 _rcl_parse_param_name(
1353  rcl_lexer_lookahead2_t * lex_lookahead,
1354  rcl_allocator_t allocator,
1355  char ** param_name)
1356 {
1357  rcl_ret_t ret;
1358  rcl_lexeme_t lexeme;
1359 
1360  // Check arguments sanity
1361  assert(NULL != lex_lookahead);
1362  assert(rcutils_allocator_is_valid(&allocator));
1363  assert(NULL != param_name);
1364  assert(NULL == *param_name);
1365 
1366  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1367  if (NULL == name_start) {
1368  RCL_SET_ERROR_MSG("failed to get start of param name");
1369  return RCL_RET_ERROR;
1370  }
1371 
1372  // token ( '.' token )*
1373  ret = _rcl_parse_param_name_token(lex_lookahead);
1374  if (RCL_RET_OK != ret) {
1375  return ret;
1376  }
1377  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1378  if (RCL_RET_OK != ret) {
1379  return ret;
1380  }
1381  while (RCL_LEXEME_SEPARATOR != lexeme) {
1382  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_DOT, NULL, NULL);
1383  if (RCL_RET_WRONG_LEXEME == ret) {
1385  }
1386  ret = _rcl_parse_param_name_token(lex_lookahead);
1387  if (RCL_RET_OK != ret) {
1388  return ret;
1389  }
1390  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1391  if (RCL_RET_OK != ret) {
1392  return ret;
1393  }
1394  }
1395 
1396  // Copy param name
1397  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1398  const size_t length = (size_t)(name_end - name_start);
1399  *param_name = rcutils_strndup(name_start, length, allocator);
1400  if (NULL == *param_name) {
1401  RCL_SET_ERROR_MSG("failed to copy param name");
1402  return RCL_RET_BAD_ALLOC;
1403  }
1404 
1405  return RCL_RET_OK;
1406 }
1407 
1408 
1410 
1413 RCL_LOCAL
1414 rcl_ret_t
1415 _rcl_parse_remap_match_name(
1416  rcl_lexer_lookahead2_t * lex_lookahead,
1417  rcl_remap_t * rule)
1418 {
1419  rcl_ret_t ret;
1420  rcl_lexeme_t lexeme;
1421 
1422  // Check arguments sanity
1423  assert(NULL != lex_lookahead);
1424  assert(NULL != rule);
1425 
1426  // rostopic:// rosservice://
1427  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1428  if (RCL_RET_OK != ret) {
1429  return ret;
1430  }
1431  if (RCL_LEXEME_URL_SERVICE == lexeme) {
1432  rule->impl->type = RCL_SERVICE_REMAP;
1433  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1434  } else if (RCL_LEXEME_URL_TOPIC == lexeme) {
1435  rule->impl->type = RCL_TOPIC_REMAP;
1436  ret = rcl_lexer_lookahead2_accept(lex_lookahead, NULL, NULL);
1437  } else {
1438  rule->impl->type = (RCL_TOPIC_REMAP | RCL_SERVICE_REMAP);
1439  }
1440  if (RCL_RET_OK != ret) {
1441  return ret;
1442  }
1443 
1444  ret = _rcl_parse_resource_match(
1445  lex_lookahead, rule->impl->allocator, &rule->impl->match);
1446  if (RCL_RET_WRONG_LEXEME == ret) {
1448  }
1449  return ret;
1450 }
1451 
1453 
1456 RCL_LOCAL
1457 rcl_ret_t
1458 _rcl_parse_remap_name_remap(
1459  rcl_lexer_lookahead2_t * lex_lookahead,
1460  rcl_remap_t * rule)
1461 {
1462  rcl_ret_t ret;
1463 
1464  // Check arguments sanity
1465  assert(NULL != lex_lookahead);
1466  assert(NULL != rule);
1467 
1468  // match
1469  ret = _rcl_parse_remap_match_name(lex_lookahead, rule);
1470  if (RCL_RET_OK != ret) {
1471  return ret;
1472  }
1473  // :=
1474  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1475  if (RCL_RET_WRONG_LEXEME == ret) {
1477  }
1478  // replacement
1479  ret = _rcl_parse_remap_replacement_name(lex_lookahead, rule);
1480  if (RCL_RET_OK != ret) {
1481  return ret;
1482  }
1483 
1484  return RCL_RET_OK;
1485 }
1486 
1488 
1491 RCL_LOCAL
1492 rcl_ret_t
1493 _rcl_parse_remap_namespace_replacement(
1494  rcl_lexer_lookahead2_t * lex_lookahead,
1495  rcl_remap_t * rule)
1496 {
1497  rcl_ret_t ret;
1498 
1499  // Check arguments sanity
1500  assert(NULL != lex_lookahead);
1501  assert(NULL != rule);
1502 
1503  // __ns
1504  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NS, NULL, NULL);
1505  if (RCL_RET_WRONG_LEXEME == ret) {
1507  }
1508  // :=
1509  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1510  if (RCL_RET_WRONG_LEXEME == ret) {
1512  }
1513  // /foo/bar
1514  const char * ns_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1515  if (NULL == ns_start) {
1516  RCL_SET_ERROR_MSG("failed to get start of namespace");
1517  return RCL_RET_ERROR;
1518  }
1519  ret = _rcl_parse_remap_fully_qualified_namespace(lex_lookahead);
1520  if (RCL_RET_OK != ret) {
1521  if (RCL_RET_INVALID_REMAP_RULE == ret) {
1522  // The name didn't start with a leading forward slash
1523  RCUTILS_LOG_WARN_NAMED(
1524  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1525  }
1526  return ret;
1527  }
1528  // There should be nothing left
1529  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1530  if (RCL_RET_OK != ret) {
1531  // The name must have started with a leading forward slash but had an otherwise invalid format
1532  RCUTILS_LOG_WARN_NAMED(
1533  ROS_PACKAGE_NAME, "Namespace not remapped to a fully qualified name (found: %s)", ns_start);
1534  return ret;
1535  }
1536 
1537  // Copy namespace into rule
1538  const char * ns_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1539  size_t length = (size_t)(ns_end - ns_start);
1540  rule->impl->replacement = rcutils_strndup(ns_start, length, rule->impl->allocator);
1541  if (NULL == rule->impl->replacement) {
1542  RCL_SET_ERROR_MSG("failed to copy namespace");
1543  return RCL_RET_BAD_ALLOC;
1544  }
1545 
1546  rule->impl->type = RCL_NAMESPACE_REMAP;
1547  return RCL_RET_OK;
1548 }
1549 
1551 
1554 RCL_LOCAL
1555 rcl_ret_t
1556 _rcl_parse_remap_nodename_replacement(
1557  rcl_lexer_lookahead2_t * lex_lookahead,
1558  rcl_remap_t * rule)
1559 {
1560  rcl_ret_t ret;
1561  const char * node_name;
1562  size_t length;
1563 
1564  // Check arguments sanity
1565  assert(NULL != lex_lookahead);
1566  assert(NULL != rule);
1567 
1568  // __node
1569  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_NODE, NULL, NULL);
1570  if (RCL_RET_WRONG_LEXEME == ret) {
1572  }
1573  // :=
1574  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1575  if (RCL_RET_WRONG_LEXEME == ret) {
1577  }
1578  // new_node_name
1579  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &node_name, &length);
1580  if (RCL_RET_WRONG_LEXEME == ret) {
1581  node_name = rcl_lexer_lookahead2_get_text(lex_lookahead);
1582  RCUTILS_LOG_WARN_NAMED(
1583  ROS_PACKAGE_NAME, "Node name not remapped to invalid name: '%s'", node_name);
1585  }
1586  if (RCL_RET_OK != ret) {
1587  return ret;
1588  }
1589  // copy the node name into the replacement side of the rule
1590  rule->impl->replacement = rcutils_strndup(node_name, length, rule->impl->allocator);
1591  if (NULL == rule->impl->replacement) {
1592  RCL_SET_ERROR_MSG("failed to allocate node name");
1593  return RCL_RET_BAD_ALLOC;
1594  }
1595 
1596  rule->impl->type = RCL_NODENAME_REMAP;
1597  return RCL_RET_OK;
1598 }
1599 
1601 RCL_LOCAL
1602 rcl_ret_t
1603 _rcl_parse_nodename_prefix(
1604  rcl_lexer_lookahead2_t * lex_lookahead,
1605  rcl_allocator_t allocator,
1606  char ** node_name)
1607 {
1608  size_t length = 0;
1609  const char * token = NULL;
1610 
1611  // Check arguments sanity
1612  assert(NULL != lex_lookahead);
1613  assert(rcutils_allocator_is_valid(&allocator));
1614  assert(NULL != node_name);
1615  assert(NULL == *node_name);
1616 
1617  // Expect a token and a colon
1618  rcl_ret_t ret =
1619  rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_TOKEN, &token, &length);
1620  if (RCL_RET_OK != ret) {
1621  return ret;
1622  }
1623  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_COLON, NULL, NULL);
1624  if (RCL_RET_OK != ret) {
1625  return ret;
1626  }
1627 
1628  // Copy the node name
1629  *node_name = rcutils_strndup(token, length, allocator);
1630  if (NULL == *node_name) {
1631  RCL_SET_ERROR_MSG("failed to allocate node name");
1632  return RCL_RET_BAD_ALLOC;
1633  }
1634 
1635  return RCL_RET_OK;
1636 }
1637 
1639 
1643 RCL_LOCAL
1644 rcl_ret_t
1645 _rcl_parse_remap_nodename_prefix(
1646  rcl_lexer_lookahead2_t * lex_lookahead,
1647  rcl_remap_t * rule)
1648 {
1649  // Check arguments sanity
1650  assert(NULL != lex_lookahead);
1651  assert(NULL != rule);
1652 
1653  rcl_ret_t ret = _rcl_parse_nodename_prefix(
1654  lex_lookahead, rule->impl->allocator, &rule->impl->node_name);
1655  if (RCL_RET_WRONG_LEXEME == ret) {
1657  }
1658  return ret;
1659 }
1660 
1662 
1670 RCL_LOCAL
1671 rcl_ret_t
1672 _rcl_parse_remap_begin_remap_rule(
1673  rcl_lexer_lookahead2_t * lex_lookahead,
1674  rcl_remap_t * rule)
1675 {
1676  rcl_ret_t ret;
1677  rcl_lexeme_t lexeme1;
1678  rcl_lexeme_t lexeme2;
1679 
1680  // Check arguments sanity
1681  assert(NULL != lex_lookahead);
1682  assert(NULL != rule);
1683 
1684  // Check for optional nodename prefix
1685  ret = rcl_lexer_lookahead2_peek2(lex_lookahead, &lexeme1, &lexeme2);
1686  if (RCL_RET_OK != ret) {
1687  return ret;
1688  }
1689  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1690  ret = _rcl_parse_remap_nodename_prefix(lex_lookahead, rule);
1691  if (RCL_RET_OK != ret) {
1692  return ret;
1693  }
1694  }
1695 
1696  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme1);
1697  if (RCL_RET_OK != ret) {
1698  return ret;
1699  }
1700 
1701  // What type of rule is this (node name replacement, namespace replacement, or name remap)?
1702  if (RCL_LEXEME_NODE == lexeme1) {
1703  ret = _rcl_parse_remap_nodename_replacement(lex_lookahead, rule);
1704  if (RCL_RET_OK != ret) {
1705  return ret;
1706  }
1707  } else if (RCL_LEXEME_NS == lexeme1) {
1708  ret = _rcl_parse_remap_namespace_replacement(lex_lookahead, rule);
1709  if (RCL_RET_OK != ret) {
1710  return ret;
1711  }
1712  } else {
1713  ret = _rcl_parse_remap_name_remap(lex_lookahead, rule);
1714  if (RCL_RET_OK != ret) {
1715  return ret;
1716  }
1717  }
1718 
1719  // Make sure all characters in string have been consumed
1720  ret = rcl_lexer_lookahead2_expect(lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1721  if (RCL_RET_WRONG_LEXEME == ret) {
1723  }
1724  return ret;
1725 }
1726 
1727 RCL_LOCAL
1728 rcl_ret_t
1729 _rcl_parse_log_level_name(
1730  rcl_lexer_lookahead2_t * lex_lookahead,
1731  rcl_allocator_t * allocator,
1732  char ** logger_name)
1733 {
1734  rcl_lexeme_t lexeme;
1735 
1736  // Check arguments sanity
1737  assert(NULL != lex_lookahead);
1738  assert(rcutils_allocator_is_valid(allocator));
1739  assert(NULL != logger_name);
1740  assert(NULL == *logger_name);
1741 
1742  const char * name_start = rcl_lexer_lookahead2_get_text(lex_lookahead);
1743  if (NULL == name_start) {
1744  RCL_SET_ERROR_MSG("failed to get start of logger name");
1745  return RCL_RET_ERROR;
1746  }
1747 
1748  rcl_ret_t ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1749  if (RCL_RET_OK != ret) {
1750  return ret;
1751  }
1752 
1753  while (RCL_LEXEME_SEPARATOR != lexeme) {
1754  ret = rcl_lexer_lookahead2_expect(lex_lookahead, lexeme, NULL, NULL);
1755  if (RCL_RET_OK != ret) {
1756  return ret;
1757  }
1758 
1759  ret = rcl_lexer_lookahead2_peek(lex_lookahead, &lexeme);
1760  if (RCL_RET_OK != ret) {
1761  return ret;
1762  }
1763 
1764  if (lexeme == RCL_LEXEME_EOF) {
1766  return ret;
1767  }
1768  }
1769 
1770  // Copy logger name
1771  const char * name_end = rcl_lexer_lookahead2_get_text(lex_lookahead);
1772  const size_t length = (size_t)(name_end - name_start);
1773  *logger_name = rcutils_strndup(name_start, length, *allocator);
1774  if (NULL == *logger_name) {
1775  RCL_SET_ERROR_MSG("failed to copy logger name");
1776  return RCL_RET_BAD_ALLOC;
1777  }
1778 
1779  return RCL_RET_OK;
1780 }
1781 
1782 rcl_ret_t
1783 _rcl_parse_log_level(
1784  const char * arg,
1785  rcl_log_levels_t * log_levels)
1786 {
1787  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1788  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
1789  RCL_CHECK_ARGUMENT_FOR_NULL(log_levels->logger_settings, RCL_RET_INVALID_ARGUMENT);
1790  rcl_allocator_t * allocator = &log_levels->allocator;
1791  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
1792 
1793  rcl_ret_t ret = RCL_RET_OK;
1794  char * logger_name = NULL;
1795  int level = 0;
1796  rcutils_ret_t rcutils_ret = RCUTILS_RET_OK;
1797 
1799 
1800  ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, *allocator);
1801  if (RCL_RET_OK != ret) {
1802  return ret;
1803  }
1804 
1805  ret = _rcl_parse_log_level_name(&lex_lookahead, allocator, &logger_name);
1806  if (RCL_RET_OK == ret) {
1807  if (strlen(logger_name) == 0) {
1808  RCL_SET_ERROR_MSG("Argument has an invalid logger item that name is empty");
1810  goto cleanup;
1811  }
1812 
1813  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1814  if (RCL_RET_WRONG_LEXEME == ret) {
1816  goto cleanup;
1817  }
1818 
1819  const char * level_token;
1820  size_t level_token_length;
1822  &lex_lookahead, RCL_LEXEME_TOKEN, &level_token, &level_token_length);
1823  if (RCL_RET_WRONG_LEXEME == ret) {
1825  goto cleanup;
1826  }
1827 
1828  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_EOF, NULL, NULL);
1829  if (RCL_RET_OK != ret) {
1831  goto cleanup;
1832  }
1833 
1834  rcutils_ret = rcutils_logging_severity_level_from_string(
1835  level_token, *allocator, &level);
1836  if (RCUTILS_RET_OK == rcutils_ret) {
1838  log_levels, logger_name, (rcl_log_severity_t)level);
1839  if (ret != RCL_RET_OK) {
1840  goto cleanup;
1841  }
1842  }
1843  } else {
1844  rcutils_ret = rcutils_logging_severity_level_from_string(
1845  arg, *allocator, &level);
1846  if (RCUTILS_RET_OK == rcutils_ret) {
1847  if (log_levels->default_logger_level != (rcl_log_severity_t)level) {
1848  if (log_levels->default_logger_level != RCUTILS_LOG_SEVERITY_UNSET) {
1849  RCUTILS_LOG_DEBUG_NAMED(
1850  ROS_PACKAGE_NAME, "Minimum default log level will be replaced from %d to %d",
1851  log_levels->default_logger_level, level);
1852  }
1853  log_levels->default_logger_level = (rcl_log_severity_t)level;
1854  }
1855  ret = RCL_RET_OK;
1856  }
1857  }
1858 
1859  if (RCUTILS_RET_OK != rcutils_ret) {
1860  RCL_SET_ERROR_MSG("Argument does not use a valid severity level");
1861  ret = RCL_RET_ERROR;
1862  }
1863 
1864 cleanup:
1865  if (logger_name) {
1866  allocator->deallocate(logger_name, allocator->state);
1867  }
1868  rcl_ret_t rv = rcl_lexer_lookahead2_fini(&lex_lookahead);
1869  if (RCL_RET_OK != rv) {
1870  if (RCL_RET_OK != ret) {
1871  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1872  } else {
1873  ret = rv;
1874  }
1875  }
1876 
1877  return ret;
1878 }
1879 
1880 rcl_ret_t
1881 _rcl_parse_remap_rule(
1882  const char * arg,
1883  rcl_allocator_t allocator,
1884  rcl_remap_t * output_rule)
1885 {
1886  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1887  RCL_CHECK_ARGUMENT_FOR_NULL(output_rule, RCL_RET_INVALID_ARGUMENT);
1888 
1889  output_rule->impl =
1890  allocator.allocate(sizeof(rcl_remap_impl_t), allocator.state);
1891  if (NULL == output_rule->impl) {
1892  return RCL_RET_BAD_ALLOC;
1893  }
1894  output_rule->impl->allocator = allocator;
1895  output_rule->impl->type = RCL_UNKNOWN_REMAP;
1896  output_rule->impl->node_name = NULL;
1897  output_rule->impl->match = NULL;
1898  output_rule->impl->replacement = NULL;
1899 
1901  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, allocator);
1902 
1903  if (RCL_RET_OK == ret) {
1904  ret = _rcl_parse_remap_begin_remap_rule(&lex_lookahead, output_rule);
1905 
1906  rcl_ret_t fini_ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
1907  if (RCL_RET_OK != ret) {
1908  if (RCL_RET_OK != fini_ret) {
1909  RCUTILS_LOG_ERROR_NAMED(
1910  ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1911  }
1912  } else {
1913  if (RCL_RET_OK == fini_ret) {
1914  return RCL_RET_OK;
1915  }
1916  ret = fini_ret;
1917  }
1918  }
1919 
1920  // cleanup output rule but keep first error return code
1921  if (RCL_RET_OK != rcl_remap_fini(output_rule)) {
1922  RCUTILS_LOG_ERROR_NAMED(
1923  ROS_PACKAGE_NAME, "Failed to fini remap rule after error occurred");
1924  }
1925 
1926  return ret;
1927 }
1928 
1929 rcl_ret_t
1930 _rcl_parse_param_rule(
1931  const char * arg,
1932  rcl_params_t * params)
1933 {
1934  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
1935  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
1936 
1938 
1939  rcl_ret_t ret = rcl_lexer_lookahead2_init(&lex_lookahead, arg, params->allocator);
1940  if (RCL_RET_OK != ret) {
1941  return ret;
1942  }
1943 
1944  rcl_lexeme_t lexeme1;
1945  rcl_lexeme_t lexeme2;
1946  char * node_name = NULL;
1947  char * param_name = NULL;
1948 
1949  // Check for optional nodename prefix
1950  ret = rcl_lexer_lookahead2_peek2(&lex_lookahead, &lexeme1, &lexeme2);
1951  if (RCL_RET_OK != ret) {
1952  goto cleanup;
1953  }
1954 
1955  if (RCL_LEXEME_TOKEN == lexeme1 && RCL_LEXEME_COLON == lexeme2) {
1956  ret = _rcl_parse_nodename_prefix(&lex_lookahead, params->allocator, &node_name);
1957  if (RCL_RET_OK != ret) {
1958  if (RCL_RET_WRONG_LEXEME == ret) {
1960  }
1961  goto cleanup;
1962  }
1963  } else {
1964  node_name = rcutils_strdup("/**", params->allocator);
1965  if (NULL == node_name) {
1966  ret = RCL_RET_BAD_ALLOC;
1967  goto cleanup;
1968  }
1969  }
1970 
1971  // TODO(hidmic): switch to _rcl_parse_resource_match() when parameter names
1972  // are standardized to use slashes in lieu of dots.
1973  ret = _rcl_parse_param_name(&lex_lookahead, params->allocator, &param_name);
1974  if (RCL_RET_OK != ret) {
1975  if (RCL_RET_WRONG_LEXEME == ret) {
1977  }
1978  goto cleanup;
1979  }
1980 
1981  ret = rcl_lexer_lookahead2_expect(&lex_lookahead, RCL_LEXEME_SEPARATOR, NULL, NULL);
1982  if (RCL_RET_WRONG_LEXEME == ret) {
1984  goto cleanup;
1985  }
1986 
1987  const char * yaml_value = rcl_lexer_lookahead2_get_text(&lex_lookahead);
1988  if (!rcl_parse_yaml_value(node_name, param_name, yaml_value, params)) {
1990  goto cleanup;
1991  }
1992 
1993 cleanup:
1994  params->allocator.deallocate(param_name, params->allocator.state);
1995  params->allocator.deallocate(node_name, params->allocator.state);
1996  if (RCL_RET_OK != ret) {
1997  if (RCL_RET_OK != rcl_lexer_lookahead2_fini(&lex_lookahead)) {
1998  RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini lookahead2 after error occurred");
1999  }
2000  } else {
2001  ret = rcl_lexer_lookahead2_fini(&lex_lookahead);
2002  }
2003  return ret;
2004 }
2005 
2006 rcl_ret_t
2007 _rcl_parse_param_file(
2008  const char * arg,
2009  rcl_allocator_t allocator,
2010  rcl_params_t * params,
2011  char ** param_file)
2012 {
2013  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2014  RCL_CHECK_ARGUMENT_FOR_NULL(params, RCL_RET_INVALID_ARGUMENT);
2015  RCL_CHECK_ARGUMENT_FOR_NULL(param_file, RCL_RET_INVALID_ARGUMENT);
2016  *param_file = rcutils_strdup(arg, allocator);
2017  if (NULL == *param_file) {
2018  RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path");
2019  return RCL_RET_BAD_ALLOC;
2020  }
2021  if (!rcl_parse_yaml_file(*param_file, params)) {
2022  allocator.deallocate(*param_file, allocator.state);
2023  *param_file = NULL;
2024  // Error message already set.
2025  return RCL_RET_ERROR;
2026  }
2027  return RCL_RET_OK;
2028 }
2029 
2030 rcl_ret_t
2031 _rcl_parse_external_log_file_name(
2032  const char * arg,
2033  rcl_allocator_t allocator,
2034  char ** log_file_name_prefix)
2035 {
2036  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2037  RCL_CHECK_ARGUMENT_FOR_NULL(log_file_name_prefix, RCL_RET_INVALID_ARGUMENT);
2038 
2039  *log_file_name_prefix = rcutils_strdup(arg, allocator);
2040  if (NULL == *log_file_name_prefix) {
2041  RCL_SET_ERROR_MSG("Failed to allocate memory for external log file name prefix");
2042  return RCL_RET_BAD_ALLOC;
2043  }
2044  return RCL_RET_OK;
2045 }
2046 
2047 rcl_ret_t
2048 _rcl_parse_external_log_config_file(
2049  const char * arg,
2050  rcl_allocator_t allocator,
2051  char ** log_config_file)
2052 {
2053  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2054  RCL_CHECK_ARGUMENT_FOR_NULL(log_config_file, RCL_RET_INVALID_ARGUMENT);
2055 
2056  *log_config_file = rcutils_strdup(arg, allocator);
2057  // TODO(hidmic): add file checks
2058  if (NULL == *log_config_file) {
2059  RCL_SET_ERROR_MSG("Failed to allocate memory for external log config file");
2060  return RCL_RET_BAD_ALLOC;
2061  }
2062  return RCL_RET_OK;
2063 }
2064 
2065 rcl_ret_t
2066 _rcl_parse_enclave(
2067  const char * arg,
2068  rcl_allocator_t allocator,
2069  char ** enclave)
2070 {
2071  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2072  RCL_CHECK_ARGUMENT_FOR_NULL(enclave, RCL_RET_INVALID_ARGUMENT);
2073 
2074  *enclave = rcutils_strdup(arg, allocator);
2075  if (NULL == *enclave) {
2076  RCL_SET_ERROR_MSG("Failed to allocate memory for enclave name");
2077  return RCL_RET_BAD_ALLOC;
2078  }
2079  return RCL_RET_OK;
2080 }
2081 
2082 rcl_ret_t
2083 _rcl_parse_disabling_flag(
2084  const char * arg,
2085  const char * suffix,
2086  bool * disable)
2087 {
2088  RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
2089  RCL_CHECK_ARGUMENT_FOR_NULL(suffix, RCL_RET_INVALID_ARGUMENT);
2090  RCL_CHECK_ARGUMENT_FOR_NULL(disable, RCL_RET_INVALID_ARGUMENT);
2091 
2092  const size_t enable_prefix_len = strlen(RCL_ENABLE_FLAG_PREFIX);
2093  if (
2094  strncmp(RCL_ENABLE_FLAG_PREFIX, arg, enable_prefix_len) == 0 &&
2095  strcmp(suffix, arg + enable_prefix_len) == 0)
2096  {
2097  *disable = false;
2098  return RCL_RET_OK;
2099  }
2100 
2101  const size_t disable_prefix_len = strlen(RCL_DISABLE_FLAG_PREFIX);
2102  if (
2103  strncmp(RCL_DISABLE_FLAG_PREFIX, arg, disable_prefix_len) == 0 &&
2104  strcmp(suffix, arg + disable_prefix_len) == 0)
2105  {
2106  *disable = true;
2107  return RCL_RET_OK;
2108  }
2109 
2110  RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
2111  "Argument is not a %s%s nor a %s%s flag.",
2112  RCL_ENABLE_FLAG_PREFIX, suffix,
2113  RCL_DISABLE_FLAG_PREFIX, suffix);
2114  return RCL_RET_ERROR;
2115 }
2116 
2117 rcl_ret_t
2118 _rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator)
2119 {
2120  args->impl = allocator->allocate(sizeof(rcl_arguments_impl_t), allocator->state);
2121  if (NULL == args->impl) {
2122  return RCL_RET_BAD_ALLOC;
2123  }
2124 
2125  rcl_arguments_impl_t * args_impl = args->impl;
2126  args_impl->num_remap_rules = 0;
2127  args_impl->remap_rules = NULL;
2129  args_impl->external_log_file_name_prefix = NULL;
2130  args_impl->external_log_config_file = NULL;
2131  args_impl->unparsed_args = NULL;
2132  args_impl->num_unparsed_args = 0;
2133  args_impl->unparsed_ros_args = NULL;
2134  args_impl->num_unparsed_ros_args = 0;
2135  args_impl->parameter_overrides = NULL;
2136  args_impl->parameter_files = NULL;
2137  args_impl->num_param_files_args = 0;
2138  args_impl->log_stdout_disabled = false;
2139  args_impl->log_rosout_disabled = false;
2140  args_impl->log_ext_lib_disabled = false;
2141  args_impl->enclave = NULL;
2142  args_impl->allocator = *allocator;
2143 
2144  return RCL_RET_OK;
2145 }
2146 
#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:333
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:40
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