@@ -142,6 +142,31 @@ RCUTILS_PUBLIC
142142RCUTILS_WARN_UNUSED
143143rcutils_ret_t rcutils_logging_shutdown (void );
144144
145+ /// Configures the logging system.
146+ /**
147+ * This function should be called during the ROS initialization process. It will
148+ * add the enabled log output appenders to the root logger.
149+ *
150+ * <hr>
151+ * Attribute | Adherence
152+ * ------------------ | -------------
153+ * Allocates Memory | No
154+ * Thread-Safe | No
155+ * Uses Atomics | No
156+ * Lock-Free | Yes
157+ *
158+ * \param default_level The default severity level to log at
159+ * \param config_file The configuration file for the external logging library to use. Should be a null terminated string.
160+ * If NULL or an empty string the default configuration will be used
161+ * \param enable_stdout Should the stdout output appender be enabled
162+ * \param enable_rosout Should the rosout output appender be enabled
163+ * \param enable_ext_lib Should the external logger library output appender be enabled
164+ * \return `RCUTILS_RET_OK` if successful.
165+ * \return `RCUTILS_RET_ERR` if a general error occurs
166+ */
167+ RCUTILS_PUBLIC
168+ rcutils_ret_t rcutils_logging_configure (int default_level , const char * config_file , bool enable_stdout , bool enable_rosout , bool enable_ext_lib );
169+
145170/// The structure identifying the caller location in the source code.
146171typedef struct rcutils_log_location_t
147172{
@@ -196,16 +221,14 @@ rcutils_logging_severity_level_from_string(
196221 * \param severity The severity level
197222 * \param name The name of the logger
198223 * \param timestamp The timestamp
199- * \param format The format string
200- * \param args The variable argument list
224+ * \param log_str The string to be logged
201225 */
202226typedef void (* rcutils_logging_output_handler_t )(
203227 const rcutils_log_location_t * , // location
204228 int , // severity
205229 const char * , // name
206230 rcutils_time_point_value_t , // timestamp
207- const char * , // format
208- va_list * // args
231+ const char * // log_str
209232);
210233
211234/// The function pointer of the current output handler.
@@ -418,7 +441,8 @@ int rcutils_logging_get_logger_effective_level(const char * name);
418441 * <hr>
419442 * Attribute | Adherence
420443 * ------------------ | -------------
421- * Allocates Memory | No
444+ * Allocates Memory | No, for formatted outputs <= 1023 characters
445+ * | Yes, for formatted outputs >= 1024 characters
422446 * Thread-Safe | No
423447 * Uses Atomics | No
424448 * Lock-Free | Yes
@@ -449,8 +473,7 @@ void rcutils_log(
449473 * <hr>
450474 * Attribute | Adherence
451475 * ------------------ | -------------
452- * Allocates Memory | No, for formatted outputs <= 1023 characters
453- * | Yes, for formatted outputs >= 1024 characters
476+ * Allocates Memory | No
454477 * Thread-Safe | Yes, if the underlying *printf functions are
455478 * Uses Atomics | No
456479 * Lock-Free | Yes
@@ -459,14 +482,13 @@ void rcutils_log(
459482 * \param severity The severity level
460483 * \param name The name of the logger, must be null terminated c string
461484 * \param timestamp The timestamp for when the log message was made
462- * \param format The format string for the message contents
463- * \param args The variable argument list for the message format string
485+ * \param log_str The string to be logged
464486 */
465487RCUTILS_PUBLIC
466488void rcutils_logging_console_output_handler (
467489 const rcutils_log_location_t * location ,
468490 int severity , const char * name , rcutils_time_point_value_t timestamp ,
469- const char * format , va_list * args );
491+ const char * log_str );
470492
471493// Provide the compiler with branch prediction information
472494#ifndef _WIN32
0 commit comments