-
Notifications
You must be signed in to change notification settings - Fork 162
/
arguments.c
2024 lines (1827 loc) · 64.3 KB
/
arguments.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
// Copyright 2018 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
/// \cond INTERNAL // Internal Doxygen documentation
#include "rcl/arguments.h"
#include <assert.h>
#include <string.h>
#include "./arguments_impl.h"
#include "./remap_impl.h"
#include "rcl/error_handling.h"
#include "rcl/lexer_lookahead.h"
#include "rcl/validate_topic_name.h"
#include "rcl_yaml_param_parser/parser.h"
#include "rcl_yaml_param_parser/types.h"
#include "rcutils/allocator.h"
#include "rcutils/error_handling.h"
#include "rcutils/format_string.h"
#include "rcutils/logging.h"
#include "rcutils/logging_macros.h"
#include "rcutils/strdup.h"
#include "rmw/validate_namespace.h"
#include "rmw/validate_node_name.h"
#ifdef __cplusplus
extern "C"
{
#endif
/// Parse an argument that may or may not be a remap rule.
/**
* \param[in] arg the argument to parse
* \param[in] allocator an allocator to use
* \param[in,out] output_rule input a zero intialized rule, output a fully initialized one
* \return RCL_RET_OK if a valid rule was parsed, or
* \return RCL_RET_INVALID_REMAP_RULE if the argument is not a valid rule, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_remap_rule(
const char * arg,
rcl_allocator_t allocator,
rcl_remap_t * output_rule);
/// Parse an argument that may or may not be a param rule.
/**
* \param[in] arg the argument to parse
* \param[in,out] params param overrides structure to populate.
* This structure must have been initialized by the caller.
* \return RCL_RET_OK if a valid rule was parsed, or
* \return RCL_RET_INVALID_ARGUMENT if an argument is invalid, or
* \return RCL_RET_INVALID_PARAM_RULE if the argument is not a valid rule, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
rcl_ret_t
_rcl_parse_param_rule(
const char * arg,
rcl_params_t * params);
rcl_ret_t
rcl_arguments_get_param_files(
const rcl_arguments_t * arguments,
rcl_allocator_t allocator,
char *** parameter_files)
{
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(parameter_files, RCL_RET_INVALID_ARGUMENT);
*(parameter_files) = allocator.allocate(
sizeof(char *) * arguments->impl->num_param_files_args, allocator.state);
if (NULL == *parameter_files) {
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < arguments->impl->num_param_files_args; ++i) {
(*parameter_files)[i] = rcutils_strdup(arguments->impl->parameter_files[i], allocator);
if (NULL == (*parameter_files)[i]) {
// deallocate allocated memory
for (int r = i; r >= 0; --r) {
allocator.deallocate((*parameter_files)[r], allocator.state);
}
allocator.deallocate((*parameter_files), allocator.state);
(*parameter_files) = NULL;
return RCL_RET_BAD_ALLOC;
}
}
return RCL_RET_OK;
}
int
rcl_arguments_get_param_files_count(
const rcl_arguments_t * args)
{
if (NULL == args || NULL == args->impl) {
return -1;
}
return args->impl->num_param_files_args;
}
rcl_ret_t
rcl_arguments_get_param_overrides(
const rcl_arguments_t * arguments,
rcl_params_t ** parameter_overrides)
{
RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(parameter_overrides, RCL_RET_INVALID_ARGUMENT);
if (NULL != *parameter_overrides) {
RCL_SET_ERROR_MSG("Output parameter override pointer is not null. May leak memory.");
return RCL_RET_INVALID_ARGUMENT;
}
*parameter_overrides = NULL;
if (NULL != arguments->impl->parameter_overrides) {
*parameter_overrides = rcl_yaml_node_struct_copy(arguments->impl->parameter_overrides);
if (NULL == *parameter_overrides) {
return RCL_RET_BAD_ALLOC;
}
}
return RCL_RET_OK;
}
rcl_ret_t
rcl_arguments_get_log_levels(
const rcl_arguments_t * arguments,
rcl_log_levels_t * log_levels)
{
RCL_CHECK_ARGUMENT_FOR_NULL(arguments, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(arguments->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(log_levels, RCL_RET_INVALID_ARGUMENT);
const rcl_allocator_t * allocator = &arguments->impl->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
return rcl_log_levels_copy(&arguments->impl->log_levels, log_levels);
}
/// Parse an argument that may or may not be a log level rule.
/**
* \param[in] arg the argument to parse
* \param[in,out] log_levels parsed a default logger level or a logger setting
* \return RCL_RET_OK if a valid log level was parsed, or
* \return RCL_RET_INVALID_LOG_LEVEL_RULE if the argument is not a valid rule, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_log_level(
const char * arg,
rcl_log_levels_t * log_levels);
/// Parse an argument that may or may not be a log configuration file.
/**
* \param[in] arg the argument to parse
* \param[in] allocator an allocator to use
* \param[in,out] log_config_file parsed log configuration file
* \return RCL_RET_OK if a valid log config file was parsed, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_external_log_config_file(
const char * arg,
rcl_allocator_t allocator,
char ** log_config_file);
/// Parse an argument that may or may not be a parameter file.
/**
* The syntax of the file name is not validated.
* \param[in] arg the argument to parse
* \param[in] allocator an allocator to use
* \param[in] params points to the populated parameter struct
* \param[in,out] param_file string that could be a parameter file name
* \return RCL_RET_OK if the rule was parsed correctly, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_param_file(
const char * arg,
rcl_allocator_t allocator,
rcl_params_t * params,
char ** param_file);
/// Parse an enclave argument.
/**
* \param[in] arg the argument to parse
* \param[in] allocator an allocator to use
* \param[in,out] enclave parsed security enclave
* \return RCL_RET_OK if a valid security enclave was parsed, or
* \return RCL_RET_BAD_ALLOC if an allocation failed, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_enclave(
const char * arg,
rcl_allocator_t allocator,
char ** enclave);
#define RCL_ENABLE_FLAG_PREFIX "--enable-"
#define RCL_DISABLE_FLAG_PREFIX "--disable-"
/// Parse a bool argument that may or may not be for the provided key rule.
/**
* \param[in] arg the argument to parse
* \param[in] key the key for the argument to parse. Should be a null terminated string
* \param[in,out] value parsed boolean value
* \return RCL_RET_OK if the bool argument was parsed successfully, or
* \return RLC_RET_ERROR if an unspecified error occurred.
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_disabling_flag(
const char * arg,
const char * key,
bool * value);
/// Allocate and zero initialize arguments impl and.
/**
* \param[out] args target arguments to set impl
* \param[in] allocator an allocator to use
* \return RCL_RET_OK if a valid rule was parsed, or
* \return RCL_RET_BAD_ALLOC if an allocation failed
*/
rcl_ret_t
_rcl_allocate_initialized_arguments_impl(rcl_arguments_t * args, rcl_allocator_t * allocator);
rcl_ret_t
rcl_parse_arguments(
int argc,
const char * const argv[],
rcl_allocator_t allocator,
rcl_arguments_t * args_output)
{
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
if (argc < 0) {
RCL_SET_ERROR_MSG("Argument count cannot be negative");
return RCL_RET_INVALID_ARGUMENT;
} else if (argc > 0) {
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
}
RCL_CHECK_ARGUMENT_FOR_NULL(args_output, RCL_RET_INVALID_ARGUMENT);
if (args_output->impl != NULL) {
RCL_SET_ERROR_MSG("Parse output is not zero-initialized");
return RCL_RET_INVALID_ARGUMENT;
}
rcl_ret_t ret;
rcl_ret_t fail_ret;
ret = _rcl_allocate_initialized_arguments_impl(args_output, &allocator);
if (RCL_RET_OK != ret) {
return ret;
}
rcl_arguments_impl_t * args_impl = args_output->impl;
if (argc == 0) {
// there are no arguments to parse
return RCL_RET_OK;
}
// over-allocate arrays to match the number of arguments
args_impl->remap_rules = allocator.allocate(sizeof(rcl_remap_t) * argc, allocator.state);
if (NULL == args_impl->remap_rules) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->parameter_overrides = rcl_yaml_node_struct_init(allocator);
if (NULL == args_impl->parameter_overrides) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->parameter_files = allocator.allocate(sizeof(char *) * argc, allocator.state);
if (NULL == args_impl->parameter_files) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->unparsed_ros_args = allocator.allocate(sizeof(int) * argc, allocator.state);
if (NULL == args_impl->unparsed_ros_args) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
args_impl->unparsed_args = allocator.allocate(sizeof(int) * argc, allocator.state);
if (NULL == args_impl->unparsed_args) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
rcl_log_levels_t log_levels = rcl_get_zero_initialized_log_levels();
ret = rcl_log_levels_init(&log_levels, &allocator, argc);
if (ret != RCL_RET_OK) {
goto fail;
}
args_impl->log_levels = log_levels;
bool parsing_ros_args = false;
for (int i = 0; i < argc; ++i) {
if (parsing_ros_args) {
// Ignore ROS specific arguments flags
if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
continue;
}
// Check for ROS specific arguments explicit end token
if (strcmp(RCL_ROS_ARGS_EXPLICIT_END_TOKEN, argv[i]) == 0) {
parsing_ros_args = false;
continue;
}
// Attempt to parse argument as parameter override flag
if (strcmp(RCL_PARAM_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_PARAM_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
// Attempt to parse next argument as parameter override rule
if (RCL_RET_OK == _rcl_parse_param_rule(argv[i + 1], args_impl->parameter_overrides)) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Got param override rule : %s\n", argv[i + 1]);
++i; // Skip flag here, for loop will skip rule.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse parameter override rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing %s flag. No parameter override rule found.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
i, argv[i], RCL_PARAM_FLAG, RCL_SHORT_PARAM_FLAG);
// Attempt to parse argument as remap rule flag
if (strcmp(RCL_REMAP_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_REMAP_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
// Attempt to parse next argument as remap rule
rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
*rule = rcl_get_zero_initialized_remap();
if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i + 1], allocator, rule)) {
++(args_impl->num_remap_rules);
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
++i; // Skip flag here, for loop will skip rule.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse remap rule: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing %s flag. No remap rule found.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s nor a %s flag.",
i, argv[i], RCL_REMAP_FLAG, RCL_SHORT_REMAP_FLAG);
// Attempt to parse argument as parameter file rule
if (strcmp(RCL_PARAM_FILE_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
// Attempt to parse next argument as parameter file rule
args_impl->parameter_files[args_impl->num_param_files_args] = NULL;
if (
RCL_RET_OK == _rcl_parse_param_file(
argv[i + 1], allocator, args_impl->parameter_overrides,
&args_impl->parameter_files[args_impl->num_param_files_args]))
{
++(args_impl->num_param_files_args);
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
"Got params file : %s\ntotal num param files %d",
args_impl->parameter_files[args_impl->num_param_files_args - 1],
args_impl->num_param_files_args);
++i; // Skip flag here, for loop will skip rule.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse params file: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing %s flag. No file path provided.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
i, argv[i], RCL_PARAM_FILE_FLAG);
// Attempt to parse argument as log level configuration
if (strcmp(RCL_LOG_LEVEL_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
if (RCL_RET_OK ==
_rcl_parse_log_level(argv[i + 1], &args_impl->log_levels))
{
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got log level: %s\n", argv[i + 1]);
++i; // Skip flag here, for loop will skip value.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse log level: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing log level flag: '%s'. No log level provided.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
i, argv[i], RCL_LOG_LEVEL_FLAG);
// Attempt to parse argument as log configuration file
if (strcmp(RCL_EXTERNAL_LOG_CONFIG_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
if (NULL != args_impl->external_log_config_file) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Overriding log configuration file : %s\n",
args_impl->external_log_config_file);
allocator.deallocate(args_impl->external_log_config_file, allocator.state);
args_impl->external_log_config_file = NULL;
}
if (RCL_RET_OK == _rcl_parse_external_log_config_file(
argv[i + 1], allocator, &args_impl->external_log_config_file))
{
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Got log configuration file : %s\n",
args_impl->external_log_config_file);
++i; // Skip flag here, for loop will skip value.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse log configuration file: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing %s flag. No file path provided.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
// Attempt to parse argument as a security enclave
if (strcmp(RCL_ENCLAVE_FLAG, argv[i]) == 0 || strcmp(RCL_SHORT_ENCLAVE_FLAG, argv[i]) == 0) {
if (i + 1 < argc) {
if (NULL != args_impl->enclave) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Overriding security enclave : %s\n",
args_impl->enclave);
allocator.deallocate(args_impl->enclave, allocator.state);
args_impl->enclave = NULL;
}
if (RCL_RET_OK == _rcl_parse_enclave(
argv[i + 1], allocator, &args_impl->enclave))
{
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Got enclave: %s\n",
args_impl->enclave);
++i; // Skip flag here, for loop will skip value.
continue;
}
rcl_error_string_t prev_error_string = rcl_get_error_string();
rcl_reset_error();
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse enclave name: '%s %s'. Error: %s", argv[i], argv[i + 1],
prev_error_string.str);
} else {
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Couldn't parse trailing %s flag. No enclave path provided.", argv[i]);
}
ret = RCL_RET_INVALID_ROS_ARGS;
goto fail;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Arg %d (%s) is not a %s flag.",
i, argv[i], RCL_EXTERNAL_LOG_CONFIG_FLAG);
// Attempt to parse --enable/disable-stdout-logs flag
ret = _rcl_parse_disabling_flag(
argv[i], RCL_LOG_STDOUT_FLAG_SUFFIX, &args_impl->log_stdout_disabled);
if (RCL_RET_OK == ret) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Disable log stdout ? %s\n",
args_impl->log_stdout_disabled ? "true" : "false");
continue;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX,
RCL_DISABLE_FLAG_PREFIX, RCL_LOG_STDOUT_FLAG_SUFFIX, rcl_get_error_string().str);
rcl_reset_error();
// Attempt to parse --enable/disable-rosout-logs flag
ret = _rcl_parse_disabling_flag(
argv[i], RCL_LOG_ROSOUT_FLAG_SUFFIX, &args_impl->log_rosout_disabled);
if (RCL_RET_OK == ret) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Disable log rosout ? %s\n",
args_impl->log_rosout_disabled ? "true" : "false");
continue;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX,
RCL_DISABLE_FLAG_PREFIX, RCL_LOG_ROSOUT_FLAG_SUFFIX, rcl_get_error_string().str);
rcl_reset_error();
// Attempt to parse --enable/disable-external-lib-logs flag
ret = _rcl_parse_disabling_flag(
argv[i], RCL_LOG_EXT_LIB_FLAG_SUFFIX, &args_impl->log_ext_lib_disabled);
if (RCL_RET_OK == ret) {
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME, "Disable log external lib ? %s\n",
args_impl->log_ext_lib_disabled ? "true" : "false");
continue;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as %s%s or %s%s flag. Error: %s",
i, argv[i], RCL_ENABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX,
RCL_DISABLE_FLAG_PREFIX, RCL_LOG_EXT_LIB_FLAG_SUFFIX, rcl_get_error_string().str);
rcl_reset_error();
// Argument is an unknown ROS specific argument
args_impl->unparsed_ros_args[args_impl->num_unparsed_ros_args] = i;
++(args_impl->num_unparsed_ros_args);
} else {
// Check for ROS specific arguments flags
if (strcmp(RCL_ROS_ARGS_FLAG, argv[i]) == 0) {
parsing_ros_args = true;
continue;
}
// Attempt to parse argument as remap rule in its deprecated form
rcl_remap_t * rule = &(args_impl->remap_rules[args_impl->num_remap_rules]);
*rule = rcl_get_zero_initialized_remap();
if (RCL_RET_OK == _rcl_parse_remap_rule(argv[i], allocator, rule)) {
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"Found remap rule '%s'. This syntax is deprecated. Use '%s %s %s' instead.",
argv[i], RCL_ROS_ARGS_FLAG, RCL_REMAP_FLAG, argv[i]);
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Got remap rule : %s\n", argv[i + 1]);
++(args_impl->num_remap_rules);
continue;
}
RCUTILS_LOG_DEBUG_NAMED(
ROS_PACKAGE_NAME,
"Couldn't parse arg %d (%s) as a remap rule in its deprecated form. Error: %s",
i, argv[i], rcl_get_error_string().str);
rcl_reset_error();
// Argument is not a ROS specific argument
args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
++(args_impl->num_unparsed_args);
}
}
// Shrink remap_rules array to match number of successfully parsed rules
if (args_impl->num_remap_rules > 0) {
args_impl->remap_rules = rcutils_reallocf(
args_impl->remap_rules, sizeof(rcl_remap_t) * args_impl->num_remap_rules, &allocator);
if (NULL == args_impl->remap_rules) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
} else {
// No remap rules
allocator.deallocate(args_impl->remap_rules, allocator.state);
args_impl->remap_rules = NULL;
}
// Shrink Parameter files
if (0 == args_impl->num_param_files_args) {
allocator.deallocate(args_impl->parameter_files, allocator.state);
args_impl->parameter_files = NULL;
} else if (args_impl->num_param_files_args < argc) {
args_impl->parameter_files = rcutils_reallocf(
args_impl->parameter_files, sizeof(char *) * args_impl->num_param_files_args, &allocator);
if (NULL == args_impl->parameter_files) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
}
// Drop parameter overrides if none was found.
if (0U == args_impl->parameter_overrides->num_nodes) {
rcl_yaml_node_struct_fini(args_impl->parameter_overrides);
args_impl->parameter_overrides = NULL;
}
// Shrink unparsed_ros_args
if (0 == args_impl->num_unparsed_ros_args) {
// No unparsed ros args
allocator.deallocate(args_impl->unparsed_ros_args, allocator.state);
args_impl->unparsed_ros_args = NULL;
} else if (args_impl->num_unparsed_ros_args < argc) {
args_impl->unparsed_ros_args = rcutils_reallocf(
args_impl->unparsed_ros_args, sizeof(int) * args_impl->num_unparsed_ros_args, &allocator);
if (NULL == args_impl->unparsed_ros_args) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
}
// Shrink unparsed_args
if (0 == args_impl->num_unparsed_args) {
// No unparsed args
allocator.deallocate(args_impl->unparsed_args, allocator.state);
args_impl->unparsed_args = NULL;
} else if (args_impl->num_unparsed_args < argc) {
args_impl->unparsed_args = rcutils_reallocf(
args_impl->unparsed_args, sizeof(int) * args_impl->num_unparsed_args, &allocator);
if (NULL == args_impl->unparsed_args) {
ret = RCL_RET_BAD_ALLOC;
goto fail;
}
}
// Shrink logger settings of log levels
ret = rcl_log_levels_shrink_to_size(&args_impl->log_levels);
if (ret != RCL_RET_OK) {
goto fail;
}
return RCL_RET_OK;
fail:
fail_ret = ret;
if (NULL != args_impl) {
ret = rcl_arguments_fini(args_output);
if (RCL_RET_OK != ret) {
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to fini arguments after earlier failure");
}
}
return fail_ret;
}
int
rcl_arguments_get_count_unparsed(
const rcl_arguments_t * args)
{
if (NULL == args || NULL == args->impl) {
return -1;
}
return args->impl->num_unparsed_args;
}
rcl_ret_t
rcl_arguments_get_unparsed(
const rcl_arguments_t * args,
rcl_allocator_t allocator,
int ** output_unparsed_indices)
{
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_indices, RCL_RET_INVALID_ARGUMENT);
*output_unparsed_indices = NULL;
if (args->impl->num_unparsed_args) {
*output_unparsed_indices = allocator.allocate(
sizeof(int) * args->impl->num_unparsed_args, allocator.state);
if (NULL == *output_unparsed_indices) {
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
(*output_unparsed_indices)[i] = args->impl->unparsed_args[i];
}
}
return RCL_RET_OK;
}
int
rcl_arguments_get_count_unparsed_ros(
const rcl_arguments_t * args)
{
if (NULL == args || NULL == args->impl) {
return -1;
}
return args->impl->num_unparsed_ros_args;
}
rcl_ret_t
rcl_arguments_get_unparsed_ros(
const rcl_arguments_t * args,
rcl_allocator_t allocator,
int ** output_unparsed_ros_indices)
{
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(output_unparsed_ros_indices, RCL_RET_INVALID_ARGUMENT);
*output_unparsed_ros_indices = NULL;
if (args->impl->num_unparsed_ros_args) {
*output_unparsed_ros_indices = allocator.allocate(
sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
if (NULL == *output_unparsed_ros_indices) {
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
(*output_unparsed_ros_indices)[i] = args->impl->unparsed_ros_args[i];
}
}
return RCL_RET_OK;
}
rcl_arguments_t
rcl_get_zero_initialized_arguments(void)
{
static rcl_arguments_t default_arguments = {
.impl = NULL
};
return default_arguments;
}
rcl_ret_t
rcl_remove_ros_arguments(
char const * const argv[],
const rcl_arguments_t * args,
rcl_allocator_t allocator,
int * nonros_argc,
const char ** nonros_argv[])
{
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ALLOCATOR_WITH_MSG(&allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argc, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(nonros_argv, RCL_RET_INVALID_ARGUMENT);
if (NULL != *nonros_argv) {
RCL_SET_ERROR_MSG("Output nonros_argv pointer is not null. May leak memory.");
return RCL_RET_INVALID_ARGUMENT;
}
*nonros_argc = rcl_arguments_get_count_unparsed(args);
if (*nonros_argc < 0) {
RCL_SET_ERROR_MSG("Failed to get unparsed non ROS specific arguments count.");
return RCL_RET_INVALID_ARGUMENT;
} else if (*nonros_argc > 0) {
RCL_CHECK_ARGUMENT_FOR_NULL(argv, RCL_RET_INVALID_ARGUMENT);
}
*nonros_argv = NULL;
if (0 == *nonros_argc) {
return RCL_RET_OK;
}
int * unparsed_indices = NULL;
rcl_ret_t ret = rcl_arguments_get_unparsed(args, allocator, &unparsed_indices);
if (RCL_RET_OK != ret) {
return ret;
}
size_t alloc_size = sizeof(char *) * *nonros_argc;
*nonros_argv = allocator.allocate(alloc_size, allocator.state);
if (NULL == *nonros_argv) {
allocator.deallocate(unparsed_indices, allocator.state);
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < *nonros_argc; ++i) {
(*nonros_argv)[i] = argv[unparsed_indices[i]];
}
allocator.deallocate(unparsed_indices, allocator.state);
return RCL_RET_OK;
}
rcl_ret_t
rcl_arguments_copy(
const rcl_arguments_t * args,
rcl_arguments_t * args_out)
{
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args->impl, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(args_out, RCL_RET_INVALID_ARGUMENT);
if (NULL != args_out->impl) {
RCL_SET_ERROR_MSG("args_out must be zero initialized");
return RCL_RET_INVALID_ARGUMENT;
}
rcl_allocator_t allocator = args->impl->allocator;
rcl_ret_t ret = _rcl_allocate_initialized_arguments_impl(args_out, &allocator);
if (RCL_RET_OK != ret) {
return ret;
}
if (args->impl->num_unparsed_args) {
// Copy unparsed args
args_out->impl->unparsed_args = allocator.allocate(
sizeof(int) * args->impl->num_unparsed_args, allocator.state);
if (NULL == args_out->impl->unparsed_args) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < args->impl->num_unparsed_args; ++i) {
args_out->impl->unparsed_args[i] = args->impl->unparsed_args[i];
}
args_out->impl->num_unparsed_args = args->impl->num_unparsed_args;
}
if (args->impl->num_unparsed_ros_args) {
// Copy unparsed ROS args
args_out->impl->unparsed_ros_args = allocator.allocate(
sizeof(int) * args->impl->num_unparsed_ros_args, allocator.state);
if (NULL == args_out->impl->unparsed_ros_args) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
for (int i = 0; i < args->impl->num_unparsed_ros_args; ++i) {
args_out->impl->unparsed_ros_args[i] = args->impl->unparsed_ros_args[i];
}
args_out->impl->num_unparsed_ros_args = args->impl->num_unparsed_ros_args;
}
if (args->impl->num_remap_rules) {
// Copy remap rules
args_out->impl->remap_rules = allocator.allocate(
sizeof(rcl_remap_t) * args->impl->num_remap_rules, allocator.state);
if (NULL == args_out->impl->remap_rules) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
args_out->impl->num_remap_rules = args->impl->num_remap_rules;
for (int i = 0; i < args->impl->num_remap_rules; ++i) {
args_out->impl->remap_rules[i] = rcl_get_zero_initialized_remap();
ret = rcl_remap_copy(
&(args->impl->remap_rules[i]), &(args_out->impl->remap_rules[i]));
if (RCL_RET_OK != ret) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return ret;
}
}
}
// Copy parameter rules
if (args->impl->parameter_overrides) {
args_out->impl->parameter_overrides =
rcl_yaml_node_struct_copy(args->impl->parameter_overrides);
}
// Copy parameter files
if (args->impl->num_param_files_args) {
args_out->impl->parameter_files = allocator.allocate(
sizeof(char *) * args->impl->num_param_files_args, allocator.state);
if (NULL == args_out->impl->parameter_files) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
args_out->impl->num_param_files_args = args->impl->num_param_files_args;
for (int i = 0; i < args->impl->num_param_files_args; ++i) {
args_out->impl->parameter_files[i] =
rcutils_strdup(args->impl->parameter_files[i], allocator);
if (NULL == args_out->impl->parameter_files[i]) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
}
return RCL_RET_BAD_ALLOC;
}
}
}
char * enclave_copy = rcutils_strdup(args->impl->enclave, allocator);
if (args->impl->enclave && !enclave_copy) {
if (RCL_RET_OK != rcl_arguments_fini(args_out)) {
RCL_SET_ERROR_MSG("Error while finalizing arguments due to another error");
} else {
RCL_SET_ERROR_MSG("Error while copying enclave argument");
}
return RCL_RET_BAD_ALLOC;
}
args_out->impl->enclave = enclave_copy;
return RCL_RET_OK;
}
rcl_ret_t
rcl_arguments_fini(
rcl_arguments_t * args)
{
RCL_CHECK_ARGUMENT_FOR_NULL(args, RCL_RET_INVALID_ARGUMENT);
if (args->impl) {
rcl_ret_t ret = RCL_RET_OK;
if (args->impl->remap_rules) {
for (int i = 0; i < args->impl->num_remap_rules; ++i) {
rcl_ret_t remap_ret = rcl_remap_fini(&(args->impl->remap_rules[i]));
if (remap_ret != RCL_RET_OK) {
ret = remap_ret;
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME,
"Failed to finalize remap rule while finalizing arguments. Continuing...");
}
}
args->impl->allocator.deallocate(args->impl->remap_rules, args->impl->allocator.state);
args->impl->remap_rules = NULL;
args->impl->num_remap_rules = 0;
}
rcl_ret_t log_levels_ret = rcl_log_levels_fini(&args->impl->log_levels);
if (log_levels_ret != RCL_RET_OK) {
ret = log_levels_ret;
RCUTILS_LOG_ERROR_NAMED(
ROS_PACKAGE_NAME,
"Failed to finalize log levels while finalizing arguments. Continuing...");
}
args->impl->allocator.deallocate(args->impl->unparsed_args, args->impl->allocator.state);
args->impl->num_unparsed_args = 0;
args->impl->unparsed_args = NULL;
args->impl->allocator.deallocate(args->impl->unparsed_ros_args, args->impl->allocator.state);
args->impl->num_unparsed_ros_args = 0;
args->impl->unparsed_ros_args = NULL;
if (args->impl->parameter_overrides) {
rcl_yaml_node_struct_fini(args->impl->parameter_overrides);
args->impl->parameter_overrides = NULL;
}
if (args->impl->parameter_files) {
for (int p = 0; p < args->impl->num_param_files_args; ++p) {
args->impl->allocator.deallocate(
args->impl->parameter_files[p], args->impl->allocator.state);
}
args->impl->allocator.deallocate(args->impl->parameter_files, args->impl->allocator.state);
args->impl->num_param_files_args = 0;
args->impl->parameter_files = NULL;
}
args->impl->allocator.deallocate(args->impl->enclave, args->impl->allocator.state);
if (NULL != args->impl->external_log_config_file) {
args->impl->allocator.deallocate(
args->impl->external_log_config_file, args->impl->allocator.state);
args->impl->external_log_config_file = NULL;
}
args->impl->allocator.deallocate(args->impl, args->impl->allocator.state);
args->impl = NULL;
return ret;
}
RCL_SET_ERROR_MSG("rcl_arguments_t finalized twice");
return RCL_RET_ERROR;
}
/// Parses a fully qualified namespace for a namespace replacement rule (ex: `/foo/bar`)
/**
* \sa _rcl_parse_remap_begin_remap_rule()
*/
RCL_LOCAL
rcl_ret_t
_rcl_parse_remap_fully_qualified_namespace(
rcl_lexer_lookahead2_t * lex_lookahead)
{
rcl_ret_t ret;