-
Notifications
You must be signed in to change notification settings - Fork 100
/
logging.c
1349 lines (1178 loc) · 44.8 KB
/
logging.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 2017 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.
#include <ctype.h>
#include <errno.h>
#include <inttypes.h>
#include <stdint.h>
#include <stdio.h>
#include <string.h>
#ifdef _WIN32
# include <io.h>
// When building with MSVC 19.28.29333.0 on Windows 10 (as of 2020-11-11),
// there appears to be a problem with winbase.h (which is included by
// Windows.h). In particular, warnings of the form:
//
// warning C5105: macro expansion producing 'defined' has undefined behavior
//
// See https://developercommunity.visualstudio.com/content/problem/695656/wdk-and-sdk-are-not-compatible-with-experimentalpr.html
// for more information. For now disable that warning when including windows.h
# pragma warning(push)
# pragma warning(disable : 5105)
# include <windows.h>
# pragma warning(pop)
#else
# include <unistd.h>
#endif
#include "rcutils/allocator.h"
#include "rcutils/env.h"
#include "rcutils/error_handling.h"
#include "rcutils/find.h"
#include "rcutils/format_string.h"
#include "rcutils/logging.h"
#include "rcutils/snprintf.h"
#include "rcutils/strdup.h"
#include "rcutils/strerror.h"
#include "rcutils/time.h"
#include "rcutils/types/hash_map.h"
#define RCUTILS_LOGGING_SEPARATOR_CHAR '.'
#define RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN (2048)
#if defined(_WIN32)
// Used with setvbuf, and size must be 2 <= size <= INT_MAX. For more info, see:
// https://docs.microsoft.com/en-us/cpp/c-runtime-library/reference/setvbuf
#define RCUTILS_LOGGING_STREAM_BUFFER_SIZE (BUFSIZ)
#else
// Let the system choose the appropriate size
// glibc reference: https://sourceware.org/git/?p=glibc.git;a=blob;f=libio/iosetvbuf.c;hb=HEAD
// OSX reference: https://opensource.apple.com/source/Libc/Libc-166/stdio.subproj/setvbuf.c.auto.html
#define RCUTILS_LOGGING_STREAM_BUFFER_SIZE (0)
#endif
const char * const g_rcutils_log_severity_names[] = {
[RCUTILS_LOG_SEVERITY_UNSET] = "UNSET",
[RCUTILS_LOG_SEVERITY_DEBUG] = "DEBUG",
[RCUTILS_LOG_SEVERITY_INFO] = "INFO",
[RCUTILS_LOG_SEVERITY_WARN] = "WARN",
[RCUTILS_LOG_SEVERITY_ERROR] = "ERROR",
[RCUTILS_LOG_SEVERITY_FATAL] = "FATAL",
};
enum rcutils_colorized_output
{
RCUTILS_COLORIZED_OUTPUT_FORCE_DISABLE = 0,
RCUTILS_COLORIZED_OUTPUT_FORCE_ENABLE = 1,
RCUTILS_COLORIZED_OUTPUT_AUTO = 2,
};
bool g_rcutils_logging_initialized = false;
static char g_rcutils_logging_output_format_string[RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN];
static const char * g_rcutils_logging_default_output_format =
"[{severity}] [{time}] [{name}]: {message}";
static rcutils_allocator_t g_rcutils_logging_allocator;
static rcutils_logging_output_handler_t g_rcutils_logging_output_handler = NULL;
static rcutils_hash_map_t g_rcutils_logging_severities_map;
// If this is false, attempts to use the severities map will be skipped.
// This can happen if allocation of the map fails at initialization.
static bool g_rcutils_logging_severities_map_valid = false;
static int g_rcutils_logging_default_logger_level = 0;
static FILE * g_output_stream = NULL;
static enum rcutils_colorized_output g_colorized_output = RCUTILS_COLORIZED_OUTPUT_AUTO;
typedef struct logging_input_s
{
const char * name;
const rcutils_log_location_t * location;
const char * msg;
int severity;
rcutils_time_point_value_t timestamp;
} logging_input_t;
typedef const char * (* token_handler)(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset);
typedef struct log_msg_part_s
{
token_handler handler;
size_t start_offset;
size_t end_offset;
} log_msg_part_t;
static size_t g_num_log_msg_handlers = 0;
static log_msg_part_t g_handlers[1024];
rcutils_ret_t rcutils_logging_initialize(void)
{
return rcutils_logging_initialize_with_allocator(rcutils_get_default_allocator());
}
enum rcutils_get_env_retval
{
RCUTILS_GET_ENV_ERROR = -1,
RCUTILS_GET_ENV_ZERO = 0,
RCUTILS_GET_ENV_ONE = 1,
RCUTILS_GET_ENV_EMPTY = 2,
};
// A utility function to get zero or one from an environment variable.
// Returns RCUTILS_GET_ENV_ERROR if we failed to get the environment variable
// or if it was something we don't understand.
// Return RCUTILS_GET_ENV_ZERO if the value in the environment variable is "0",
// RCUTILS_GET_ENV_ONE if the value in the environment variable is "1", or
// RCUTILS_GET_ENV_EMPTY if the environment variables is empty.
static enum rcutils_get_env_retval rcutils_get_env_var_zero_or_one(
const char * name, const char * zero_semantic,
const char * one_semantic)
{
const char * env_var_value = NULL;
const char * ret_str = rcutils_get_env(name, &env_var_value);
if (NULL != ret_str) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Error getting environment variable %s: %s", name,
ret_str);
return RCUTILS_GET_ENV_ERROR;
}
if (strcmp(env_var_value, "") == 0) {
return RCUTILS_GET_ENV_EMPTY;
}
if (strcmp(env_var_value, "0") == 0) {
return RCUTILS_GET_ENV_ZERO;
}
if (strcmp(env_var_value, "1") == 0) {
return RCUTILS_GET_ENV_ONE;
}
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Warning: unexpected value [%s] specified for %s. "
"Valid values are 0 (%s) or 1 (%s).",
env_var_value, name, zero_semantic, one_semantic);
return RCUTILS_GET_ENV_ERROR;
}
static const char * expand_time(
const logging_input_t * logging_input, rcutils_char_array_t * logging_output,
rcutils_ret_t (* time_func)(const rcutils_time_point_value_t *, char *, size_t))
{
// Temporary, local storage for integer/float conversion to string
// Note:
// 32 characters enough, because the most it can be is 20 characters
// for the 19 possible digits in a signed 64-bit number plus the optional
// decimal point in the floating point seconds version
char numeric_storage[32];
if (time_func(
&logging_input->timestamp, numeric_storage,
sizeof(numeric_storage)) != RCUTILS_RET_OK)
{
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
if (rcutils_char_array_strcat(logging_output, numeric_storage) != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
return logging_output->buffer;
}
static const char * expand_time_as_seconds(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
return expand_time(logging_input, logging_output, rcutils_time_point_value_as_seconds_string);
}
static const char * expand_time_as_nanoseconds(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
return expand_time(logging_input, logging_output, rcutils_time_point_value_as_nanoseconds_string);
}
static const char * expand_line_number(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
if (logging_input->location) {
// Allow 9 digits for the expansion of the line number (otherwise, truncate).
char line_number_expansion[10];
// Even in the case of truncation the result will still be null-terminated.
int written = rcutils_snprintf(
line_number_expansion, sizeof(line_number_expansion), "%zu",
logging_input->location->line_number);
if (written < 0) {
RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(
"failed to format line number: '%zu'\n", logging_input->location->line_number);
return NULL;
}
if (rcutils_char_array_strcat(logging_output, line_number_expansion) != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
}
return logging_output->buffer;
}
static const char * expand_severity(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
const char * severity_string = g_rcutils_log_severity_names[logging_input->severity];
if (rcutils_char_array_strcat(logging_output, severity_string) != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
return logging_output->buffer;
}
static const char * expand_name(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
if (NULL != logging_input->name) {
if (rcutils_char_array_strcat(logging_output, logging_input->name) != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
}
return logging_output->buffer;
}
static const char * expand_message(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
if (rcutils_char_array_strcat(logging_output, logging_input->msg) != RCUTILS_RET_OK) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
return logging_output->buffer;
}
static const char * expand_function_name(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
if (logging_input->location) {
if (rcutils_char_array_strcat(
logging_output,
logging_input->location->function_name) != RCUTILS_RET_OK)
{
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
}
return logging_output->buffer;
}
static const char * expand_file_name(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)start_offset;
(void)end_offset;
if (logging_input->location) {
if (rcutils_char_array_strcat(
logging_output,
logging_input->location->file_name) != RCUTILS_RET_OK)
{
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
}
return logging_output->buffer;
}
typedef struct token_map_entry_s
{
const char * token;
token_handler handler;
} token_map_entry_t;
static const token_map_entry_t tokens[] = {
{.token = "severity", .handler = expand_severity},
{.token = "name", .handler = expand_name},
{.token = "message", .handler = expand_message},
{.token = "function_name", .handler = expand_function_name},
{.token = "file_name", .handler = expand_file_name},
{.token = "time", .handler = expand_time_as_seconds},
{.token = "time_as_nanoseconds", .handler = expand_time_as_nanoseconds},
{.token = "line_number", .handler = expand_line_number},
};
static token_handler find_token_handler(const char * token)
{
int token_number = sizeof(tokens) / sizeof(tokens[0]);
for (int token_index = 0; token_index < token_number; token_index++) {
if (strcmp(token, tokens[token_index].token) == 0) {
return tokens[token_index].handler;
}
}
return NULL;
}
static const char * copy_from_orig(
const logging_input_t * logging_input,
rcutils_char_array_t * logging_output,
size_t start_offset, size_t end_offset)
{
(void)logging_input;
if (rcutils_char_array_strncat(
logging_output,
g_rcutils_logging_output_format_string + start_offset,
end_offset - start_offset) != RCUTILS_RET_OK)
{
RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str);
rcutils_reset_error();
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
return NULL;
}
return logging_output->buffer;
}
static bool add_handler(token_handler handler, size_t start_offset, size_t end_offset)
{
if (g_num_log_msg_handlers >= (sizeof(g_handlers) / sizeof(g_handlers[0]))) {
RCUTILS_SET_ERROR_MSG("Too many substitutions in the logging output format string; truncating");
return false;
}
g_handlers[g_num_log_msg_handlers].handler = handler;
g_handlers[g_num_log_msg_handlers].start_offset = start_offset;
g_handlers[g_num_log_msg_handlers].end_offset = end_offset;
g_num_log_msg_handlers++;
return true;
}
static void parse_and_create_handlers_list(void)
{
// Process the format string looking for known tokens.
const char token_start_delimiter = '{';
const char token_end_delimiter = '}';
const char * str = g_rcutils_logging_output_format_string;
size_t size = strlen(g_rcutils_logging_output_format_string);
g_num_log_msg_handlers = 0;
// Walk through the format string and create callbacks when they're encountered.
size_t i = 0;
while (i < size) {
// Print everything up to the next token start delimiter.
size_t chars_to_start_delim = rcutils_find(str + i, token_start_delimiter);
size_t remaining_chars = size - i;
if (chars_to_start_delim > 0) { // there is stuff before a token start delimiter
size_t chars_to_copy = chars_to_start_delim >
remaining_chars ? remaining_chars : chars_to_start_delim;
if (!add_handler(copy_from_orig, i, i + chars_to_copy)) {
// The error was already set by add_handler
return;
}
i += chars_to_copy;
if (i >= size) { // perhaps no start delimiter was found
break;
}
continue;
}
// We are at a token start delimiter: determine if there's a known token or not.
// Potential tokens can't possibly be longer than the format string itself.
char token[RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN];
// Look for a token end delimiter.
size_t chars_to_end_delim = rcutils_find(str + i, token_end_delimiter);
remaining_chars = size - i;
if (chars_to_end_delim > remaining_chars) {
// No end delimiters found in the remainder of the format string;
// there won't be any more tokens so shortcut the rest of the checking.
if (!add_handler(copy_from_orig, i, i + remaining_chars)) {
// The error was already set by add_handler
return;
}
break;
}
// Found what looks like a token; determine if it's recognized.
size_t token_len = chars_to_end_delim - 1; // Not including delimiters.
memcpy(token, str + i + 1, token_len); // Skip the start delimiter.
token[token_len] = '\0';
token_handler expand_token = find_token_handler(token);
if (!expand_token) {
// This wasn't a token; print the start delimiter and continue the search as usual
// (the substring might contain more start delimiters).
if (!add_handler(copy_from_orig, i, i + 1)) {
// The error was already set by add_handler
return;
}
i++;
continue;
}
if (!add_handler(expand_token, 0, 0)) {
// The error was already set by add_handler
return;
}
// Skip ahead to avoid re-processing the token characters (including the 2 delimiters).
i += token_len + 2;
}
}
rcutils_ret_t rcutils_logging_initialize_with_allocator(rcutils_allocator_t allocator)
{
if (g_rcutils_logging_initialized) {
return RCUTILS_RET_OK;
}
if (!rcutils_allocator_is_valid(&allocator)) {
RCUTILS_SET_ERROR_MSG("Provided allocator is invalid.");
return RCUTILS_RET_INVALID_ARGUMENT;
}
g_rcutils_logging_allocator = allocator;
g_rcutils_logging_output_handler = &rcutils_logging_console_output_handler;
g_rcutils_logging_default_logger_level = RCUTILS_DEFAULT_LOGGER_DEFAULT_LEVEL;
const char * line_buffered = NULL;
const char * ret_str = rcutils_get_env("RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED", &line_buffered);
if (NULL != ret_str) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Error getting environment variable RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED: %s", ret_str);
return RCUTILS_RET_ERROR;
}
if (strcmp(line_buffered, "") != 0) {
RCUTILS_SAFE_FWRITE_TO_STDERR(
"RCUTILS_CONSOLE_STDOUT_LINE_BUFFERED is now ignored. "
"Please set RCUTILS_LOGGING_USE_STDOUT and RCUTILS_LOGGING_BUFFERED_STREAM "
"to control the stream and the buffering of log messages.\n");
}
// Set the default output stream for all severities to stderr so that errors
// are propagated immediately.
// The user can choose to set the output stream to stdout by setting the
// RCUTILS_LOGGING_USE_STDOUT environment variable to 1.
enum rcutils_get_env_retval retval = rcutils_get_env_var_zero_or_one(
"RCUTILS_LOGGING_USE_STDOUT", "use stderr", "use stdout");
switch (retval) {
case RCUTILS_GET_ENV_ERROR:
return RCUTILS_RET_INVALID_ARGUMENT;
case RCUTILS_GET_ENV_EMPTY:
case RCUTILS_GET_ENV_ZERO:
g_output_stream = stderr;
break;
case RCUTILS_GET_ENV_ONE:
g_output_stream = stdout;
break;
default:
RCUTILS_SET_ERROR_MSG(
"Invalid return from environment fetch");
return RCUTILS_RET_ERROR;
}
// Allow the user to choose how buffering on the stream works by setting
// RCUTILS_LOGGING_BUFFERED_STREAM.
// With an empty environment variable, use the default of the stream.
// With a value of 0, force the stream to be unbuffered.
// With a value of 1, force the stream to be line buffered.
retval = rcutils_get_env_var_zero_or_one(
"RCUTILS_LOGGING_BUFFERED_STREAM", "not buffered", "buffered");
if (RCUTILS_GET_ENV_ERROR == retval) {
return RCUTILS_RET_INVALID_ARGUMENT;
}
if (RCUTILS_GET_ENV_ZERO == retval || RCUTILS_GET_ENV_ONE == retval) {
int mode = retval == RCUTILS_GET_ENV_ZERO ? _IONBF : _IOLBF;
size_t buffer_size = (mode == _IOLBF) ? RCUTILS_LOGGING_STREAM_BUFFER_SIZE : 0;
// buffer_size cannot be 0 on Windows with IOLBF, see comments above where it's #define'd
if (setvbuf(g_output_stream, NULL, mode, buffer_size) != 0) {
char error_string[1024];
rcutils_strerror(error_string, sizeof(error_string));
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Error setting stream buffering mode: %s", error_string);
return RCUTILS_RET_ERROR;
}
} else if (RCUTILS_GET_ENV_EMPTY != retval) {
RCUTILS_SET_ERROR_MSG(
"Invalid return from environment fetch");
return RCUTILS_RET_ERROR;
}
retval = rcutils_get_env_var_zero_or_one(
"RCUTILS_COLORIZED_OUTPUT", "force color",
"force no color");
switch (retval) {
case RCUTILS_GET_ENV_ERROR:
return RCUTILS_RET_INVALID_ARGUMENT;
case RCUTILS_GET_ENV_EMPTY:
g_colorized_output = RCUTILS_COLORIZED_OUTPUT_AUTO;
break;
case RCUTILS_GET_ENV_ZERO:
g_colorized_output = RCUTILS_COLORIZED_OUTPUT_FORCE_DISABLE;
break;
case RCUTILS_GET_ENV_ONE:
g_colorized_output = RCUTILS_COLORIZED_OUTPUT_FORCE_ENABLE;
break;
default:
RCUTILS_SET_ERROR_MSG(
"Invalid return from environment fetch");
return RCUTILS_RET_ERROR;
}
// Check for the environment variable for custom output formatting
const char * output_format;
ret_str = rcutils_get_env("RCUTILS_CONSOLE_OUTPUT_FORMAT", &output_format);
if (NULL != ret_str) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Failed to get output format from env. variable [%s]. Using default output format.",
ret_str);
output_format = g_rcutils_logging_default_output_format;
} else {
if (strcmp(output_format, "") == 0) {
output_format = g_rcutils_logging_default_output_format;
}
}
size_t chars_to_copy = strlen(output_format);
if (chars_to_copy > RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN - 1) {
chars_to_copy = RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN - 1;
}
memcpy(g_rcutils_logging_output_format_string, output_format, chars_to_copy);
g_rcutils_logging_output_format_string[chars_to_copy] = '\0';
g_rcutils_logging_severities_map = rcutils_get_zero_initialized_hash_map();
rcutils_ret_t hash_map_ret = rcutils_hash_map_init(
&g_rcutils_logging_severities_map, 2, sizeof(const char *), sizeof(int),
rcutils_hash_map_string_hash_func, rcutils_hash_map_string_cmp_func, &allocator);
if (hash_map_ret != RCUTILS_RET_OK) {
// If an error message was set it will have been overwritten by rcutils_hash_map_init.
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Failed to initialize map for logger severities [%s]. Severities will not be configurable.",
rcutils_get_error_string().str);
g_rcutils_logging_severities_map_valid = false;
return RCUTILS_RET_ERROR;
}
parse_and_create_handlers_list();
g_rcutils_logging_severities_map_valid = true;
g_rcutils_logging_initialized = true;
return RCUTILS_RET_OK;
}
rcutils_ret_t rcutils_logging_shutdown(void)
{
if (!g_rcutils_logging_initialized) {
return RCUTILS_RET_OK;
}
rcutils_ret_t ret = RCUTILS_RET_OK;
if (g_rcutils_logging_severities_map_valid) {
// Iterate over the map, getting every key so we can free it
char * key = NULL;
int level;
rcutils_ret_t hash_map_ret = rcutils_hash_map_get_next_key_and_data(
&g_rcutils_logging_severities_map, NULL, &key, &level);
while (RCUTILS_RET_OK == hash_map_ret) {
hash_map_ret = rcutils_hash_map_unset(&g_rcutils_logging_severities_map, &key);
if (hash_map_ret != RCUTILS_RET_OK) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Failed to clear out logger severities [%s] during shutdown; memory will be leaked.",
rcutils_get_error_string().str);
break;
}
g_rcutils_logging_allocator.deallocate(key, g_rcutils_logging_allocator.state);
hash_map_ret = rcutils_hash_map_get_next_key_and_data(
&g_rcutils_logging_severities_map, NULL, &key, &level);
}
hash_map_ret = rcutils_hash_map_fini(&g_rcutils_logging_severities_map);
if (hash_map_ret != RCUTILS_RET_OK) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Failed to finalize map for logger severities: %s",
rcutils_get_error_string().str);
ret = RCUTILS_RET_LOGGING_SEVERITY_MAP_INVALID;
}
g_rcutils_logging_severities_map_valid = false;
}
g_num_log_msg_handlers = 0;
g_rcutils_logging_initialized = false;
return ret;
}
rcutils_ret_t
rcutils_logging_severity_level_from_string(
const char * severity_string, rcutils_allocator_t allocator, int * severity)
{
RCUTILS_CHECK_ALLOCATOR_WITH_MSG(
&allocator, "invalid allocator", return RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(severity_string, RCUTILS_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ARGUMENT_FOR_NULL(severity, RCUTILS_RET_INVALID_ARGUMENT);
rcutils_ret_t ret = RCUTILS_RET_LOGGING_SEVERITY_STRING_INVALID;
// Convert the input string to upper case (for case insensitivity).
char * severity_string_upper = rcutils_strdup(severity_string, allocator);
if (NULL == severity_string_upper) {
RCUTILS_SET_ERROR_MSG("failed to allocate memory for uppercase string");
return RCUTILS_RET_BAD_ALLOC;
}
for (int i = 0; severity_string_upper[i]; ++i) {
severity_string_upper[i] = (char)toupper(severity_string_upper[i]);
}
// Determine the severity value matching the severity name.
for (size_t i = 0;
i < sizeof(g_rcutils_log_severity_names) / sizeof(g_rcutils_log_severity_names[0]);
++i)
{
const char * severity_string_i = g_rcutils_log_severity_names[i];
if (severity_string_i && strcmp(severity_string_i, severity_string_upper) == 0) {
*severity = (enum RCUTILS_LOG_SEVERITY)i;
ret = RCUTILS_RET_OK;
break;
}
}
allocator.deallocate(severity_string_upper, allocator.state);
return ret;
}
rcutils_logging_output_handler_t rcutils_logging_get_output_handler(void)
{
RCUTILS_LOGGING_AUTOINIT;
return g_rcutils_logging_output_handler;
}
void rcutils_logging_set_output_handler(rcutils_logging_output_handler_t function)
{
RCUTILS_LOGGING_AUTOINIT;
g_rcutils_logging_output_handler = function;
}
int rcutils_logging_get_default_logger_level(void)
{
RCUTILS_LOGGING_AUTOINIT;
return g_rcutils_logging_default_logger_level;
}
void rcutils_logging_set_default_logger_level(int level)
{
RCUTILS_LOGGING_AUTOINIT;
if (RCUTILS_LOG_SEVERITY_UNSET == level) {
// Restore the default
level = RCUTILS_DEFAULT_LOGGER_DEFAULT_LEVEL;
}
g_rcutils_logging_default_logger_level = level;
}
int rcutils_logging_get_logger_level(const char * name)
{
RCUTILS_LOGGING_AUTOINIT;
if (NULL == name) {
return -1;
}
return rcutils_logging_get_logger_leveln(name, strlen(name));
}
static rcutils_ret_t add_key_to_hash_map(const char * name, int level, bool set_by_user)
{
const char * copy_name = name;
// Check if key already exists, to avoid extra memory allocation
// If the key already exists, then rcutils_hash_map_set will not maintain the key we give it,
// so we do not need to copy the name
bool already_exists = rcutils_hash_map_key_exists(&g_rcutils_logging_severities_map, ©_name);
if (!already_exists) {
// Copy the name to be stored, as there is no guarantee that the caller will keep it around.
copy_name = rcutils_strdup(name, g_rcutils_logging_allocator);
if (copy_name == NULL) {
// Don't report an error to the error handling machinery; some uses of this function are for
// caching so this is not necessarily fatal.
return RCUTILS_RET_ERROR;
}
}
if (set_by_user) {
// If the level was set by the user (rather than optimistically cached by the implementation),
// mark it here. When we purge the cache, we'll make sure not to purge these. The mark we
// use is setting the bottom bit; since our levels are 0, 10, 20, 30, 40, and 50, this works.
level |= 0x1;
}
rcutils_ret_t hash_map_ret =
rcutils_hash_map_set(&g_rcutils_logging_severities_map, ©_name, &level);
if (hash_map_ret != RCUTILS_RET_OK) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Error setting severity level for logger named '%s': %s",
name, rcutils_get_error_string().str);
return RCUTILS_RET_ERROR;
}
return RCUTILS_RET_OK;
}
static rcutils_ret_t get_severity_level(const char * name, int * severity)
{
rcutils_ret_t ret =
rcutils_hash_map_get(&g_rcutils_logging_severities_map, &name, severity);
if (ret != RCUTILS_RET_OK) {
// One possible response is RCUTILS_RET_NOT_FOUND, but the higher layers may be OK with that.
return ret;
}
// See the comment in add_key_to_hash_map() on why we remove the bottom bit.
(*severity) &= ~(0x1);
return RCUTILS_RET_OK;
}
int rcutils_logging_get_logger_leveln(const char * name, size_t name_length)
{
RCUTILS_LOGGING_AUTOINIT;
if (NULL == name) {
return -1;
}
// Skip the map lookup if the default was requested,
// as it can still be used even if the severity map is invalid.
if (0 == name_length) {
return g_rcutils_logging_default_logger_level;
}
if (!g_rcutils_logging_severities_map_valid) {
return RCUTILS_LOG_SEVERITY_UNSET;
}
char * short_name = rcutils_strndup(name, name_length, g_rcutils_logging_allocator);
if (short_name == NULL) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Failed to allocate memory when looking up logger level for '%s'", name);
return -1;
}
int severity;
rcutils_ret_t ret = get_severity_level(short_name, &severity);
g_rcutils_logging_allocator.deallocate(short_name, g_rcutils_logging_allocator.state);
if (ret != RCUTILS_RET_OK) {
// The error message was already set by get_severity_level
return RCUTILS_LOG_SEVERITY_UNSET;
}
return severity;
}
int rcutils_logging_get_logger_effective_level(const char * name)
{
RCUTILS_LOGGING_AUTOINIT;
if (NULL == name) {
return -1;
}
size_t hash_map_size;
rcutils_ret_t hash_map_ret = rcutils_hash_map_get_size(
&g_rcutils_logging_severities_map, &hash_map_size);
if (hash_map_ret != RCUTILS_RET_OK) {
RCUTILS_SET_ERROR_MSG_WITH_FORMAT_STRING(
"Error getting severity level for logger named '%s': %s",
name, rcutils_get_error_string().str);
return -1;
}
if (hash_map_size == 0) {
// The reason we do this extra check here is a bit tricky. The call to get_severity_level()
// below calls rcutils_hash_map_get(), which already has an optimization to return early if
// there are no entries in the map. However, the rest of this function doesn't know how to
// disambiguate between not finding this particular name in the map and there being no items in
// the map. In the former case, we need to do the additional work of looking through the
// hierarchy of loggers, while in the latter case we can short-circuit. To keep this function
// fast in the latter case, we do the disambiguation here.
return g_rcutils_logging_default_logger_level;
}
// Start by trying to find the exact name.
int severity;
rcutils_ret_t ret = get_severity_level(name, &severity);
if (ret == RCUTILS_RET_OK) {
if (severity != RCUTILS_LOG_SEVERITY_UNSET) {
return severity;
}
// If the severity is UNSET, then we go through the slow path and try to find a parent logger
// that is set. Failing that, we fall back to the default logger level.
} else if (ret != RCUTILS_RET_NOT_FOUND) {
// The error message was already set by get_severity_level
return -1;
}
// Since we didn't find the name in the fast path, fall back to the slow path where we break the
// string into substrings based on dots and look for any part that matches.
size_t substring_length = strlen(name);
char * tmp_name = rcutils_strdup(name, g_rcutils_logging_allocator);
if (tmp_name == NULL) {
RCUTILS_SAFE_FWRITE_TO_STDERR_WITH_FORMAT_STRING(
"Error copying string '%s'\n", name);
return -1;
}
severity = RCUTILS_LOG_SEVERITY_UNSET;
while (true) {
// Determine the next ancestor's FQN by removing the child's name.
size_t index_last_separator = rcutils_find_lastn(
name, RCUTILS_LOGGING_SEPARATOR_CHAR, substring_length);
if (SIZE_MAX == index_last_separator) {
// There are no more separators in the substring, so this is the last name we needed to check.
break;
}
substring_length = index_last_separator;
// Shorten the substring to be the name of the ancestor (excluding the separator).
tmp_name[index_last_separator] = '\0';
rcutils_ret_t ret = get_severity_level(tmp_name, &severity);
if (ret == RCUTILS_RET_OK) {
if (severity != RCUTILS_LOG_SEVERITY_UNSET) {
break;
}
} else if (ret != RCUTILS_RET_NOT_FOUND) {
// The error message was already set by get_severity_level
g_rcutils_logging_allocator.deallocate(tmp_name, g_rcutils_logging_allocator.state);
return -1;
}
}
g_rcutils_logging_allocator.deallocate(tmp_name, g_rcutils_logging_allocator.state);
if (severity == RCUTILS_LOG_SEVERITY_UNSET) {
// Neither the logger nor its ancestors have had their level specified.
severity = g_rcutils_logging_default_logger_level;
}
// TODO(wjwwood): restore or replace this optimization when thread-safety is addressed
// see: https://github.com/ros2/rcutils/pull/393
// // If the calculated severity is anything but UNSET, we place it into the hashmap for speedier
// // lookup next time. If the severity is UNSET, we don't bother because we are going to have to
// // walk the hierarchy next time anyway.
// if (severity != RCUTILS_LOG_SEVERITY_UNSET) {
// ret = add_key_to_hash_map(name, severity, false);
// if (ret != RCUTILS_RET_OK) {
// // Continue on if we failed to add the key to the hashmap.
// // This will affect performance but is not fatal.
// RCUTILS_SAFE_FWRITE_TO_STDERR(
// "Failed to cache severity; this is not fatal but will impact performance\n");
// }
// }
return severity;
}
rcutils_ret_t rcutils_logging_set_logger_level(const char * name, int level)
{
RCUTILS_LOGGING_AUTOINIT;
if (NULL == name) {
RCUTILS_SET_ERROR_MSG("Invalid logger name");
return RCUTILS_RET_INVALID_ARGUMENT;
}
if (!g_rcutils_logging_severities_map_valid) {
RCUTILS_SET_ERROR_MSG("Logger severity level map is invalid");
return RCUTILS_RET_LOGGING_SEVERITY_MAP_INVALID;
}
// Convert the severity value into a string for storage.
if (level < 0 ||
level >=
(int)(sizeof(g_rcutils_log_severity_names) / sizeof(g_rcutils_log_severity_names[0])))
{
RCUTILS_SET_ERROR_MSG("Invalid severity level specified for logger");
return RCUTILS_RET_INVALID_ARGUMENT;
}
const char * severity_string = g_rcutils_log_severity_names[level];
if (NULL == severity_string) {
RCUTILS_SET_ERROR_MSG("Unable to determine severity_string for severity");
return RCUTILS_RET_INVALID_ARGUMENT;
}
size_t name_length = strlen(name);
if (rcutils_hash_map_key_exists(&g_rcutils_logging_severities_map, &name)) {
// Iterate over the entire contents of the severities map, looking for entries that start with
// this key name. For any ones that match, check whether the user explicitly set them. If the
// user did not set it, then we cached it and so we can throw it away.
char * key = NULL;
int tmp_level;