ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
logging.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 
15 #ifdef __cplusplus
16 extern "C"
17 {
18 #endif
19 
20 #include <ctype.h>
21 #include <inttypes.h>
22 #include <stdint.h>
23 #include <string.h>
24 
25 #include "./arguments_impl.h"
26 #include "rcl/allocator.h"
27 #include "rcl/error_handling.h"
28 #include "rcl/logging.h"
29 #include "rcl/logging_rosout.h"
30 #include "rcl/macros.h"
31 #include "rcl_logging_interface/rcl_logging_interface.h"
32 #include "rcutils/logging.h"
33 #include "rcutils/time.h"
34 
35 #define RCL_LOGGING_MAX_OUTPUT_FUNCS (4)
36 
37 static rcutils_logging_output_handler_t
38  g_rcl_logging_out_handlers[RCL_LOGGING_MAX_OUTPUT_FUNCS] = {0};
39 
40 static uint8_t g_rcl_logging_num_out_handlers = 0;
41 static rcl_allocator_t g_logging_allocator;
42 static bool g_rcl_logging_stdout_enabled = false;
43 static bool g_rcl_logging_rosout_enabled = false;
44 static bool g_rcl_logging_ext_lib_enabled = false;
45 
49 static
50 void
51 rcl_logging_ext_lib_output_handler(
52  const rcutils_log_location_t * location,
53  int severity, const char * name, rcutils_time_point_value_t timestamp,
54  const char * format, va_list * args);
55 
58  const rcl_arguments_t * global_args,
59  const rcl_allocator_t * allocator,
60  rcl_logging_output_handler_t output_handler)
61 {
62  RCL_CHECK_ARGUMENT_FOR_NULL(global_args, RCL_RET_INVALID_ARGUMENT);
63  RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
64  RCL_CHECK_ARGUMENT_FOR_NULL(output_handler, RCL_RET_INVALID_ARGUMENT);
65  RCUTILS_LOGGING_AUTOINIT_WITH_ALLOCATOR(*allocator);
66  g_logging_allocator = *allocator;
67  int default_level = -1;
68  rcl_log_levels_t * log_levels = &global_args->impl->log_levels;
69  const char * file_name_prefix = global_args->impl->external_log_file_name_prefix;
70  const char * config_file = global_args->impl->external_log_config_file;
71  g_rcl_logging_stdout_enabled = !global_args->impl->log_stdout_disabled;
72  g_rcl_logging_rosout_enabled = !global_args->impl->log_rosout_disabled;
73  g_rcl_logging_ext_lib_enabled = !global_args->impl->log_ext_lib_disabled;
74  rcl_ret_t status = RCL_RET_OK;
75  g_rcl_logging_num_out_handlers = 0;
76 
77  if (log_levels) {
78  if (log_levels->default_logger_level != RCUTILS_LOG_SEVERITY_UNSET) {
79  default_level = (int)log_levels->default_logger_level;
80  rcutils_logging_set_default_logger_level(default_level);
81  }
82 
83  for (size_t i = 0; i < log_levels->num_logger_settings; ++i) {
84  rcutils_ret_t rcutils_status = rcutils_logging_set_logger_level(
85  log_levels->logger_settings[i].name,
86  (int)log_levels->logger_settings[i].level);
87  if (RCUTILS_RET_OK != rcutils_status) {
88  return RCL_RET_ERROR;
89  }
90  }
91  }
92  if (g_rcl_logging_stdout_enabled) {
93  g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
94  rcutils_logging_console_output_handler;
95  }
96  if (g_rcl_logging_rosout_enabled) {
97  status = rcl_logging_rosout_init(allocator);
98  if (RCL_RET_OK == status) {
99  g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
101  }
102  }
103  if (g_rcl_logging_ext_lib_enabled) {
104  status = rcl_logging_external_initialize(
105  file_name_prefix, config_file, g_logging_allocator);
106  if (RCL_RET_OK == status) {
107  rcl_logging_ret_t logging_status = rcl_logging_external_set_logger_level(
108  NULL, default_level);
109  if (RCL_LOGGING_RET_OK != logging_status) {
110  status = RCL_RET_ERROR;
111  }
112  g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
113  rcl_logging_ext_lib_output_handler;
114  }
115  }
116  rcutils_logging_set_output_handler(output_handler);
117  return status;
118 }
119 
120 rcl_ret_t
121 rcl_logging_configure(const rcl_arguments_t * global_args, const rcl_allocator_t * allocator)
122 {
124  global_args, allocator, &rcl_logging_multiple_output_handler);
125 }
126 
128 {
129  rcl_ret_t status = RCL_RET_OK;
130  rcutils_logging_set_output_handler(rcutils_logging_console_output_handler);
131  // In order to output log message to `rcutils_logging_console_output_handler`
132  // and `rcl_logging_ext_lib_output_handler` is not called after `rcl_logging_fini`,
133  // in addition to calling `rcutils_logging_set_output_handler`,
134  // the `g_rcl_logging_num_out_handlers` and `g_rcl_logging_out_handlers` must be updated.
135  g_rcl_logging_num_out_handlers = 1;
136  g_rcl_logging_out_handlers[0] = rcutils_logging_console_output_handler;
137 
138  if (g_rcl_logging_rosout_enabled) {
139  status = rcl_logging_rosout_fini();
140  }
141  if (RCL_RET_OK == status && g_rcl_logging_ext_lib_enabled) {
142  status = rcl_logging_external_shutdown();
143  }
144 
145  return status;
146 }
147 
149 {
150  return g_rcl_logging_rosout_enabled;
151 }
152 
153 void
155  const rcutils_log_location_t * location,
156  int severity, const char * name, rcutils_time_point_value_t timestamp,
157  const char * format, va_list * args)
158 {
159  for (uint8_t i = 0;
160  i < g_rcl_logging_num_out_handlers && NULL != g_rcl_logging_out_handlers[i]; ++i)
161  {
162  g_rcl_logging_out_handlers[i](location, severity, name, timestamp, format, args);
163  }
164 }
165 
166 static
167 void
168 rcl_logging_ext_lib_output_handler(
169  const rcutils_log_location_t * location,
170  int severity,
171  const char * name,
172  rcutils_time_point_value_t timestamp,
173  const char * format,
174  va_list * args)
175 {
176  rcl_ret_t status;
177  char msg_buf[1024] = "";
178  rcutils_char_array_t msg_array = {
179  .buffer = msg_buf,
180  .owns_buffer = false,
181  .buffer_length = 0u,
182  .buffer_capacity = sizeof(msg_buf),
183  .allocator = g_logging_allocator
184  };
185 
186  char output_buf[1024] = "";
187  rcutils_char_array_t output_array = {
188  .buffer = output_buf,
189  .owns_buffer = false,
190  .buffer_length = 0u,
191  .buffer_capacity = sizeof(output_buf),
192  .allocator = g_logging_allocator
193  };
194 
195  status = rcutils_char_array_vsprintf(&msg_array, format, *args);
196 
197  if (RCL_RET_OK == status) {
198  status = rcutils_logging_format_message(
199  location, severity, name, timestamp, msg_array.buffer, &output_array);
200  if (RCL_RET_OK != status) {
201  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to format log message: ");
202  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
203  rcl_reset_error();
204  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
205  }
206  } else {
207  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to format user log message: ");
208  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
209  rcl_reset_error();
210  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
211  }
212  rcl_logging_external_log(severity, name, output_array.buffer);
213  status = rcutils_char_array_fini(&msg_array);
214  if (RCL_RET_OK != status) {
215  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to finalize char array: ");
216  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
217  rcl_reset_error();
218  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
219  }
220  status = rcutils_char_array_fini(&output_array);
221  if (RCL_RET_OK != status) {
222  RCUTILS_SAFE_FWRITE_TO_STDERR("failed to finalize char array: ");
223  RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
224  rcl_reset_error();
225  RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
226  }
227 }
228 
229 #ifdef __cplusplus
230 }
231 #endif
#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 bool rcl_logging_rosout_enabled(void)
See if logging rosout is enabled.
Definition: logging.c:148
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_configure(const rcl_arguments_t *global_args, const rcl_allocator_t *allocator)
Configure the logging system.
Definition: logging.c:121
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_fini(void)
Definition: logging.c:127
rcutils_logging_output_handler_t rcl_logging_output_handler_t
The function signature to log messages.
Definition: logging.h:34
RCL_PUBLIC void rcl_logging_multiple_output_handler(const rcutils_log_location_t *location, int severity, const char *name, rcutils_time_point_value_t timestamp, const char *format, va_list *args)
Default output handler used by rcl.
Definition: logging.c:154
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_configure_with_output_handler(const rcl_arguments_t *global_args, const rcl_allocator_t *allocator, rcl_logging_output_handler_t output_handler)
Configure the logging system with the provided output handler.
Definition: logging.c:57
RCL_PUBLIC void rcl_logging_rosout_output_handler(const rcutils_log_location_t *location, int severity, const char *name, rcutils_time_point_value_t timestamp, const char *format, va_list *args)
The output handler outputs log messages to rosout topics.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_fini(void)
Uninitializes the rcl_logging_rosout features.
RCL_PUBLIC RCL_WARN_UNUSED rcl_ret_t rcl_logging_rosout_init(const rcl_allocator_t *allocator)
Initializes the rcl_logging_rosout features.
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.
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.
bool log_ext_lib_disabled
A boolean value indicating if the external lib handler should be used for log output.
char * external_log_file_name_prefix
A prefix used to external log file name.
Hold output of parsing command line arguments.
Definition: arguments.h:36
rcl_arguments_impl_t * impl
Private implementation pointer.
Definition: arguments.h:38
Hold default logger level and other logger setting.
Definition: log_level.h:44
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
size_t num_logger_settings
Number of logger settings.
Definition: log_level.h:50
rcl_log_severity_t level
Minimum log level severity of the logger.
Definition: log_level.h:39
const char * name
Name for the logger.
Definition: log_level.h:37
#define RCL_RET_OK
Success return code.
Definition: types.h:27
#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