From 2b68388ca8db00efef1b0eb93f34a2f05d6f13bc Mon Sep 17 00:00:00 2001 From: burekn Date: Tue, 27 Nov 2018 20:45:41 -0800 Subject: [PATCH] Moving the external logging library and rosout functions out to rcl. Also automatically uncrustifying and fixing unit tests. --- CMakeLists.txt | 7 - ...et_default_rc_logging_implementation.cmake | 46 ---- include/rcutils/logging.h | 25 --- include/rcutils/logging_external_interface.h | 66 ------ include/rcutils/types/char_array.h | 5 +- package.xml | 3 - src/char_array.c | 61 +++-- src/logging.c | 209 ++++++------------ test/test_logging.cpp | 4 +- test/test_logging_macros.c | 8 +- test/test_logging_macros.cpp | 12 +- 11 files changed, 113 insertions(+), 333 deletions(-) delete mode 100644 cmake/get_default_rc_logging_implementation.cmake delete mode 100644 include/rcutils/logging_external_interface.h diff --git a/CMakeLists.txt b/CMakeLists.txt index 49322d02..619d80c4 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,14 +11,9 @@ if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD 14) endif() -include(cmake/get_default_rc_logging_implementation.cmake) - - find_package(ament_cmake_python REQUIRED) find_package(ament_cmake_ros REQUIRED) -get_default_rc_logging_implementation(RC_LOGGING_IMPL) - ament_python_install_package(${PROJECT_NAME}) include_directories(include) @@ -96,8 +91,6 @@ add_library( ${PROJECT_NAME} ${rcutils_sources}) -target_link_libraries(${PROJECT_NAME} ${${RC_LOGGING_IMPL}_LIBRARIES}) - # Causes the visibility macros to use dllexport rather than dllimport, # which is appropriate when building the dll but not consuming it. target_compile_definitions(${PROJECT_NAME} PRIVATE "RCUTILS_BUILDING_DLL") diff --git a/cmake/get_default_rc_logging_implementation.cmake b/cmake/get_default_rc_logging_implementation.cmake deleted file mode 100644 index cfceab51..00000000 --- a/cmake/get_default_rc_logging_implementation.cmake +++ /dev/null @@ -1,46 +0,0 @@ -# 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. - -# -# Get the package name of the default logging implementation. -# -# Either selecting it using the variable RC_LOGGING_IMPLEMENTATION or -# choosing a default from the available implementations. -# -# :param var: the output variable name containing the package name -# :type var: string -# -macro(get_default_rc_logging_implementation var) - - # if logging implementation already specified or RC_LOGGING_IMPLEMENTATION environment variable is set then use that, - # otherwise default to using rc_logging_log4cxx - if(NOT "${RC_LOGGING_IMPLEMENTATION}" STREQUAL "") - set(_logging_implementation "${RC_LOGGING_IMPLEMENTATION}") - elseif(NOT "$ENV{RC_LOGGING_IMPLEMENTATION}" STREQUAL "") - set(_logging_implementation "$ENV{RC_LOGGING_IMPLEMENTATION}") - else() - set(_logging_implementation rc_logging_log4cxx) - endif() - - # persist implementation decision in cache - # if it was not determined dynamically - set( - RC_LOGGING_IMPLEMENTATION "${_logging_implementation}" - CACHE STRING "Select ROS middleware implementation to link against" FORCE - ) - - find_package("${_logging_implementation}" REQUIRED) - - set(${var} ${_logging_implementation}) -endmacro() diff --git a/include/rcutils/logging.h b/include/rcutils/logging.h index 0760331d..f688b5df 100644 --- a/include/rcutils/logging.h +++ b/include/rcutils/logging.h @@ -142,31 +142,6 @@ RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t rcutils_logging_shutdown(void); -/// Configures the logging system. -/** - * This function should be called during the ROS initialization process. It will - * add the enabled log output appenders to the root logger. - * - *
- * Attribute | Adherence - * ------------------ | ------------- - * Allocates Memory | No - * Thread-Safe | No - * Uses Atomics | No - * Lock-Free | Yes - * - * \param default_level The default severity level to log at - * \param config_file The configuration file for the external logging library to use. Should be a null terminated string. - * If NULL or an empty string the default configuration will be used - * \param enable_stdout Should the stdout output appender be enabled - * \param enable_rosout Should the rosout output appender be enabled - * \param enable_ext_lib Should the external logger library output appender be enabled - * \return `RCUTILS_RET_OK` if successful. - * \return `RCUTILS_RET_ERR` if a general error occurs - */ -RCUTILS_PUBLIC -rcutils_ret_t rcutils_logging_configure(int default_level, const char * config_file, bool enable_stdout, bool enable_rosout, bool enable_ext_lib); - /// The structure identifying the caller location in the source code. typedef struct rcutils_log_location_t { diff --git a/include/rcutils/logging_external_interface.h b/include/rcutils/logging_external_interface.h deleted file mode 100644 index 765b97fe..00000000 --- a/include/rcutils/logging_external_interface.h +++ /dev/null @@ -1,66 +0,0 @@ -// 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. - -#ifndef RCUTILS_LOGGING_EXTERNAL_INTERFACE_H_ -#define RCUTILS_LOGGING_EXTERNAL_INTERFACE_H_ - -#include -#include "rcutils/types/rcutils_ret.h" -#include "rcutils/visibility_control.h" - - -/** - * \brief Initializes the external logging library. - * - * \param config_file The location of a config file that the external logging library should use to configure itself. - * If no config file is provided this will be set to an empty string. Must be a NULL terminated c string. - * \return RC_EXTERNAL_LOGGING_RET_OK if initialized successfully or an error code if not. - */ -RCUTILS_PUBLIC -rcutils_ret_t rcutils_logging_external_initialize(const char * config_file); - -/** - * \brief Free the resources allocated for the external logging system. - * This puts the system into a state equivalent to being uninitialized - * - * \return RC_EXTERNAL_LOGGING_RET_OK if successfully shutdown or an error code if not. - */ -RCUTILS_PUBLIC -rcutils_ret_t rcutils_logging_external_shutdown(); - -/** - * \brief Logs a message - * - * \param severity The severity level of the message being logged - * \param name The name of the logger, must be a null terminated c string or NULL. If NULL or empty the root logger will - * be used. - * \param msg The message to be logged. Must be a null terminated c string. - */ -RCUTILS_PUBLIC -void rcutils_logging_external_log(int severity, const char * name, const char * msg); - - -/** - * \brief Set the severity level for a logger. - * Sets the severity level for the specified logger. If the name provided is an empty string or NULL it will change the - * level of the root logger. - * - * \param name The name of the logger. Must be a NULL terminated c string or NULL. - * \param level - The severity level to be used for the specified logger - * \return RC_EXTERNAL_LOGGING_RET_OK if set successfully or an error code if not. - */ -RCUTILS_PUBLIC -rcutils_ret_t rcutils_logging_external_set_logger_level(const char * name, int level); - -#endif diff --git a/include/rcutils/types/char_array.h b/include/rcutils/types/char_array.h index 02ef3061..121924a5 100644 --- a/include/rcutils/types/char_array.h +++ b/include/rcutils/types/char_array.h @@ -21,6 +21,7 @@ extern "C" #endif #include + #include "rcutils/allocator.h" #include "rcutils/types/rcutils_ret.h" #include "rcutils/visibility_control.h" @@ -134,7 +135,7 @@ rcutils_char_array_resize(rcutils_char_array_t * char_array, size_t new_size); RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t -rcutils_char_array_expand_as_needed(rcutils_char_array_t *char_array, size_t new_size); +rcutils_char_array_expand_as_needed(rcutils_char_array_t * char_array, size_t new_size); /// Produce output according to format and args. /** @@ -154,7 +155,7 @@ rcutils_char_array_expand_as_needed(rcutils_char_array_t *char_array, size_t new RCUTILS_PUBLIC RCUTILS_WARN_UNUSED rcutils_ret_t -rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char *format, va_list args); +rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char * format, va_list args); /// Append a string (or part of it) to the string in buffer. /** diff --git a/package.xml b/package.xml index cbe1a03e..ba64ed95 100644 --- a/package.xml +++ b/package.xml @@ -10,9 +10,6 @@ ament_cmake_ros python3-empy - rc_logging_log4cxx - rc_logging_packages - ament_cmake_gmock ament_cmake_gtest ament_cmake_pytest diff --git a/src/char_array.c b/src/char_array.c index b6acd668..6ecf6ead 100644 --- a/src/char_array.c +++ b/src/char_array.c @@ -18,18 +18,6 @@ #define MIN(a, b) ((a) < (b) ? (a) : (b)) -#define RCUTILS_VALIDATE_CHAR_ARRAY(char_array) \ - RCUTILS_CHECK_FOR_NULL_WITH_MSG( \ - char_array, \ - "char array pointer is null", \ - return RCUTILS_RET_ERROR); - -#define RCUTILS_VALIDATE_ALLOCATOR(allocator) \ - if (!rcutils_allocator_is_valid(allocator)) { \ - RCUTILS_SET_ERROR_MSG("char array has no valid allocator"); \ - return RCUTILS_RET_ERROR; \ - } - rcutils_char_array_t rcutils_get_zero_initialized_char_array(void) { @@ -49,8 +37,9 @@ rcutils_char_array_init( size_t buffer_capacity, const rcutils_allocator_t * allocator) { - RCUTILS_VALIDATE_CHAR_ARRAY(char_array); - RCUTILS_VALIDATE_ALLOCATOR(allocator); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(char_array, RCUTILS_RET_ERROR); + RCUTILS_CHECK_ALLOCATOR_WITH_MSG(allocator, "char array has no valid allocator", + return RCUTILS_RET_ERROR); char_array->owns_buffer = true; char_array->buffer_length = 0lu; @@ -74,16 +63,16 @@ rcutils_char_array_init( rcutils_ret_t rcutils_char_array_fini(rcutils_char_array_t * char_array) { - RCUTILS_VALIDATE_CHAR_ARRAY(char_array); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(char_array, RCUTILS_RET_ERROR); - if (!char_array->owns_buffer) { - return RCUTILS_RET_OK; - } + if (char_array->owns_buffer) { + rcutils_allocator_t * allocator = &char_array->allocator; + RCUTILS_CHECK_ALLOCATOR_WITH_MSG(allocator, "char array has no valid allocator", + return RCUTILS_RET_ERROR); - rcutils_allocator_t * allocator = &char_array->allocator; - RCUTILS_VALIDATE_ALLOCATOR(allocator); + allocator->deallocate(char_array->buffer, allocator->state); + } - allocator->deallocate(char_array->buffer, allocator->state); char_array->buffer = NULL; char_array->buffer_length = 0lu; char_array->buffer_capacity = 0lu; @@ -94,7 +83,7 @@ rcutils_char_array_fini(rcutils_char_array_t * char_array) rcutils_ret_t rcutils_char_array_resize(rcutils_char_array_t * char_array, size_t new_size) { - RCUTILS_VALIDATE_CHAR_ARRAY(char_array); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(char_array, RCUTILS_RET_ERROR); if (0lu == new_size) { RCUTILS_SET_ERROR_MSG("new size of char_array has to be greater than zero"); @@ -102,7 +91,8 @@ rcutils_char_array_resize(rcutils_char_array_t * char_array, size_t new_size) } rcutils_allocator_t * allocator = &char_array->allocator; - RCUTILS_VALIDATE_ALLOCATOR(allocator); + RCUTILS_CHECK_ALLOCATOR_WITH_MSG(allocator, "char array has no valid allocator", + return RCUTILS_RET_ERROR); if (new_size == char_array->buffer_capacity) { // nothing to do here @@ -113,13 +103,13 @@ rcutils_char_array_resize(rcutils_char_array_t * char_array, size_t new_size) size_t old_size = char_array->buffer_capacity; size_t old_length = char_array->buffer_length; - if (char_array->owns_buffer) { // we own the buffer, we can do whatever we want + if (char_array->owns_buffer) { // we own the buffer, we can do whatever we want char_array->buffer = rcutils_reallocf(char_array->buffer, new_size * sizeof(char), allocator); RCUTILS_CHECK_FOR_NULL_WITH_MSG( - char_array->buffer, - "failed to reallocate memory for char array", - return RCUTILS_RET_BAD_ALLOC); - } else { // we don't realloc memory we don't own. instead, we alloc some new space + char_array->buffer, + "failed to reallocate memory for char array", + return RCUTILS_RET_BAD_ALLOC); + } else { // we don't realloc memory we don't own. instead, we alloc some new space rcutils_ret_t ret = rcutils_char_array_init(char_array, new_size, allocator); if (ret != RCUTILS_RET_OK) { return ret; @@ -136,9 +126,9 @@ rcutils_char_array_resize(rcutils_char_array_t * char_array, size_t new_size) } rcutils_ret_t -rcutils_char_array_expand_as_needed(rcutils_char_array_t *char_array, size_t new_size) +rcutils_char_array_expand_as_needed(rcutils_char_array_t * char_array, size_t new_size) { - RCUTILS_VALIDATE_CHAR_ARRAY(char_array); + RCUTILS_CHECK_ARGUMENT_FOR_NULL(char_array, RCUTILS_RET_ERROR); if (new_size <= char_array->buffer_capacity) { return RCUTILS_RET_OK; @@ -148,12 +138,13 @@ rcutils_char_array_expand_as_needed(rcutils_char_array_t *char_array, size_t new } static int -_rcutils_char_array_vsprintf(rcutils_char_array_t *char_array, const char *format, va_list args) +_rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char * format, va_list args) { va_list args_clone; va_copy(args_clone, args); - // when doing size calculation, remember the return value of vsnprintf excludes terminating null byte + // when doing size calculation, remember the return value of vsnprintf excludes terminating null + // byte int size = vsnprintf(char_array->buffer, char_array->buffer_capacity, format, args_clone); va_end(args_clone); @@ -162,7 +153,7 @@ _rcutils_char_array_vsprintf(rcutils_char_array_t *char_array, const char *forma } rcutils_ret_t -rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char *format, va_list args) +rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char * format, va_list args) { int size = _rcutils_char_array_vsprintf(char_array, format, args); @@ -171,7 +162,7 @@ rcutils_char_array_vsprintf(rcutils_char_array_t * char_array, const char *forma return RCUTILS_RET_ERROR; } - size_t new_size = (size_t) size + 1; // with the terminating null byte + size_t new_size = (size_t) size + 1; // with the terminating null byte if (new_size > char_array->buffer_capacity) { rcutils_ret_t ret = rcutils_char_array_expand_as_needed(char_array, new_size); @@ -211,7 +202,7 @@ rcutils_char_array_memcpy(rcutils_char_array_t * char_array, const char * src, s rcutils_ret_t rcutils_char_array_strcpy(rcutils_char_array_t * char_array, const char * src) { - return rcutils_char_array_memcpy(char_array, src, strlen(src) + 1); + return rcutils_char_array_memcpy(char_array, src, strlen(src) + 1); } rcutils_ret_t diff --git a/src/logging.c b/src/logging.c index 234db289..3de1b89f 100644 --- a/src/logging.c +++ b/src/logging.c @@ -32,10 +32,8 @@ extern "C" #include "rcutils/strdup.h" #include "rcutils/time.h" #include "rcutils/types/string_map.h" -#include "rcutils/logging_external_interface.h" -#define RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN (2048) -#define RCUTILS_LOGGING_MAX_OUTPUT_FUNCS (3) +#define RCUTILS_LOGGING_MAX_OUTPUT_FORMAT_LEN (2048) const char * g_rcutils_log_severity_names[] = { [RCUTILS_LOG_SEVERITY_UNSET] = "UNSET", @@ -55,8 +53,6 @@ static rcutils_allocator_t g_rcutils_logging_allocator; rcutils_logging_output_handler_t g_rcutils_logging_output_handler = NULL; static rcutils_string_map_t g_rcutils_logging_severities_map; -static rcutils_logging_output_handler_t g_rcutils_logging_out_handlers[RCUTILS_LOGGING_MAX_OUTPUT_FUNCS] = {0}; -static uint8_t g_rcutils_logging_num_out_handlers = 0; // If this is false, attempts to use the severities map will be skipped. // This can happen if allocation of the map fails at initialization. @@ -67,34 +63,11 @@ int g_rcutils_logging_default_logger_level = 0; bool g_force_stdout_line_buffered = false; bool g_stdout_flush_failure_reported = false; -/** - * An output function that sends to multiple output appenders - */ -static void rcutils_logging_multiple_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str); - -/** - * An output function that sends to the external logger library - */ -static void rcutils_logging_ext_lib_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str); - -/** - * An output function that sends to the rosout topic - */ -static void rcutils_logging_rosout_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str); - /** * Handles formatting the log data into a common string format for every logger */ -static void format_log(const rcutils_log_location_t * location, +static void format_log( + const rcutils_log_location_t * location, int severity, const char * name, rcutils_time_point_value_t timestamp, const char * format, va_list * args, rcutils_char_array_t * logging_output); @@ -194,29 +167,6 @@ rcutils_ret_t rcutils_logging_shutdown(void) return ret; } -rcutils_ret_t rcutils_logging_configure(int default_level, const char * config_file, bool enable_stdout, bool enable_rosout, bool enable_ext_lib) -{ - RCUTILS_LOGGING_AUTOINIT - rcutils_ret_t status = RCUTILS_RET_OK; - if (default_level >= 0) { - rcutils_logging_set_default_logger_level(default_level); - } - if (enable_stdout) { - g_rcutils_logging_out_handlers[g_rcutils_logging_num_out_handlers++] = rcutils_logging_console_output_handler; - } - if (enable_rosout) { - g_rcutils_logging_out_handlers[g_rcutils_logging_num_out_handlers++] = rcutils_logging_rosout_output_handler; - } - if (enable_ext_lib) { - status = rcutils_logging_external_initialize(config_file); - if (RCUTILS_RET_OK == status) { - g_rcutils_logging_out_handlers[g_rcutils_logging_num_out_handlers++] = rcutils_logging_ext_lib_output_handler; - } - } - rcutils_logging_set_output_handler(rcutils_logging_multiple_output_handler); - return status; -} - rcutils_ret_t rcutils_logging_severity_level_from_string( const char * severity_string, rcutils_allocator_t allocator, int * severity) @@ -289,6 +239,9 @@ void rcutils_logging_set_default_logger_level(int 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)); } @@ -421,10 +374,10 @@ bool rcutils_logging_logger_is_enabled_for(const char * name, int severity) return severity >= logger_level; } #define SAFE_FWRITE_TO_STDERR_AND(action) \ - RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str); \ - rcutils_reset_error(); \ - RCUTILS_SAFE_FWRITE_TO_STDERR("\n"); \ - action; + RCUTILS_SAFE_FWRITE_TO_STDERR(rcutils_get_error_string().str); \ + rcutils_reset_error(); \ + RCUTILS_SAFE_FWRITE_TO_STDERR("\n"); \ + action; #define OK_OR_RETURN_NULL(op) \ if (op != RCUTILS_RET_OK) { \ @@ -433,7 +386,7 @@ bool rcutils_logging_logger_is_enabled_for(const char * name, int severity) #define OK_OR_RETURN_EARLY(op) \ if (op != RCUTILS_RET_OK) { \ - SAFE_FWRITE_TO_STDERR_AND(return); \ + SAFE_FWRITE_TO_STDERR_AND(return ); \ } #define APPEND_AND_RETURN_LOG_OUTPUT(s) \ @@ -475,51 +428,9 @@ void rcutils_log( if (rcutils_char_array_fini(&logging_output) != RCUTILS_RET_OK) { SAFE_FWRITE_TO_STDERR_AND(fprintf(stderr, "Error: failed to clean up rcutils char array.\n")); } - - } -} - -static void rcutils_logging_multiple_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str) -{ - for (uint8_t i = 0; i < g_rcutils_logging_num_out_handlers && NULL != g_rcutils_logging_out_handlers[i]; ++i) { - g_rcutils_logging_out_handlers[i](location, severity, name, timestamp, log_str); } } -/** - * An output function that sends to the external logger library - */ -static void rcutils_logging_ext_lib_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str) -{ - RCUTILS_UNUSED(location); - RCUTILS_UNUSED(severity); - RCUTILS_UNUSED(name); - RCUTILS_UNUSED(timestamp); - rcutils_logging_external_log(severity, name, log_str); -} - -/** - * An output function that sends to the rosout topic - */ -static void rcutils_logging_rosout_output_handler( - const rcutils_log_location_t * location, - int severity, const char * name, rcutils_time_point_value_t timestamp, - const char * log_str) -{ - //TODO: - RCUTILS_UNUSED(location); - RCUTILS_UNUSED(severity); - RCUTILS_UNUSED(name); - RCUTILS_UNUSED(timestamp); - RCUTILS_UNUSED(log_str); -} - typedef struct logging_input { const char * name; @@ -530,7 +441,9 @@ typedef struct logging_input rcutils_time_point_value_t timestamp; } logging_input; -typedef const char * (*token_handler)(const logging_input * logging_input, rcutils_char_array_t * logging_output); +typedef const char * (* token_handler)( + const logging_input * logging_input, + rcutils_char_array_t * logging_output); typedef struct token_map_entry { @@ -538,8 +451,9 @@ typedef struct token_map_entry token_handler handler; } token_map_entry; -const char * expand_time(const logging_input *logging_input, rcutils_char_array_t *logging_output, - rcutils_ret_t (*time_func)(const rcutils_time_point_value_t *, char *, size_t)) +const char * expand_time( + const logging_input * 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: @@ -551,17 +465,23 @@ const char * expand_time(const logging_input *logging_input, rcutils_char_array_ APPEND_AND_RETURN_LOG_OUTPUT(numeric_storage); } -const char * expand_time_as_seconds(const logging_input * logging_input, rcutils_char_array_t *logging_output) +const char * expand_time_as_seconds( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { return expand_time(logging_input, logging_output, rcutils_time_point_value_as_seconds_string); } -const char * expand_time_as_nanoseconds(const logging_input * logging_input, rcutils_char_array_t *logging_output) +const char * expand_time_as_nanoseconds( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { return expand_time(logging_input, logging_output, rcutils_time_point_value_as_nanoseconds_string); } -const char * expand_line_number(const logging_input * logging_input, rcutils_char_array_t *logging_output) +const char * expand_line_number( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { // Allow 9 digits for the expansion of the line number (otherwise, truncate). char line_number_expansion[10]; @@ -574,7 +494,8 @@ const char * expand_line_number(const logging_input * logging_input, rcutils_cha } // 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", location->line_number); + int written = rcutils_snprintf(line_number_expansion, sizeof(line_number_expansion), "%zu", + location->line_number); if (written < 0) { fprintf(stderr, "failed to format line number: '%zu'\n", location->line_number); return NULL; @@ -583,7 +504,9 @@ const char * expand_line_number(const logging_input * logging_input, rcutils_cha APPEND_AND_RETURN_LOG_OUTPUT(line_number_expansion); } -const char * expand_severity(const logging_input * logging_input, rcutils_char_array_t * logging_output) +const char * expand_severity( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { const char * severity_string = g_rcutils_log_severity_names[logging_input->severity]; APPEND_AND_RETURN_LOG_OUTPUT(severity_string); @@ -591,23 +514,30 @@ const char * expand_severity(const logging_input * logging_input, rcutils_char_a const char * expand_name(const logging_input * logging_input, rcutils_char_array_t * logging_output) { - APPEND_AND_RETURN_LOG_OUTPUT(logging_input->name); + if (NULL != logging_input->name) { + APPEND_AND_RETURN_LOG_OUTPUT(logging_input->name); + } + return logging_output->buffer; } -const char * expand_message(const logging_input * logging_input, rcutils_char_array_t * logging_output) +const char * expand_message( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { char buf[1024] = ""; rcutils_char_array_t message_buffer = { - .buffer = buf, - .owns_buffer = false, - .buffer_length = 0u, - .buffer_capacity = sizeof(buf), - .allocator = g_rcutils_logging_allocator + .buffer = buf, + .owns_buffer = false, + .buffer_length = 0u, + .buffer_capacity = sizeof(buf), + .allocator = g_rcutils_logging_allocator }; char * ret = NULL; - if (rcutils_char_array_vsprintf(&message_buffer, logging_input->format, *(logging_input->args)) == RCUTILS_RET_OK) { + if (rcutils_char_array_vsprintf(&message_buffer, logging_input->format, + *(logging_input->args)) == RCUTILS_RET_OK) + { if (rcutils_char_array_strcat(logging_output, message_buffer.buffer) == RCUTILS_RET_OK) { ret = logging_output->buffer; } @@ -618,7 +548,9 @@ const char * expand_message(const logging_input * logging_input, rcutils_char_ar return ret; } -const char * expand_function_name(const logging_input * logging_input, rcutils_char_array_t * logging_output) +const char * expand_function_name( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { if (logging_input->location) { APPEND_AND_RETURN_LOG_OUTPUT(logging_input->location->function_name); @@ -626,7 +558,9 @@ const char * expand_function_name(const logging_input * logging_input, rcutils_c return logging_output->buffer; } -const char * expand_file_name(const logging_input * logging_input, rcutils_char_array_t * logging_output) +const char * expand_file_name( + const logging_input * logging_input, + rcutils_char_array_t * logging_output) { if (logging_input->location) { APPEND_AND_RETURN_LOG_OUTPUT(logging_input->location->file_name); @@ -635,14 +569,14 @@ const char * expand_file_name(const logging_input * logging_input, rcutils_char_ } static const token_map_entry 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}, + {.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}, }; token_handler find_token_handler(const char * token) @@ -656,7 +590,8 @@ token_handler find_token_handler(const char * token) return NULL; } -static void format_log(const rcutils_log_location_t * location, +static void format_log( + const rcutils_log_location_t * location, int severity, const char * name, rcutils_time_point_value_t timestamp, const char * format, va_list * args, rcutils_char_array_t * logging_output) { @@ -668,12 +603,12 @@ static void format_log(const rcutils_log_location_t * location, size_t size = strlen(g_rcutils_logging_output_format_string); const logging_input logging_input = { - .location = location, - .severity = severity, - .name = name, - .timestamp = timestamp, - .format = format, - .args = args + .location = location, + .severity = severity, + .name = name, + .timestamp = timestamp, + .format = format, + .args = args }; // Walk through the format string and expand tokens when they're encountered. @@ -683,11 +618,12 @@ static void format_log(const rcutils_log_location_t * location, 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 are stuff before a token start delimiter - size_t chars_to_copy = chars_to_start_delim > remaining_chars ? remaining_chars : chars_to_start_delim; + if (chars_to_start_delim > 0) { // there are stuff before a token start delimiter + size_t chars_to_copy = chars_to_start_delim > + remaining_chars ? remaining_chars : chars_to_start_delim; OK_OR_RETURN_EARLY(rcutils_char_array_strncat(logging_output, str + i, chars_to_copy)); i += chars_to_copy; - if (i >= size) { // perhaps no start delimiter was found + if (i >= size) { // perhaps no start delimiter was found break; } } @@ -728,7 +664,6 @@ static void format_log(const rcutils_log_location_t * location, // Skip ahead to avoid re-processing the token characters (including the 2 delimiters). i += token_len + 2; } - } void rcutils_logging_console_output_handler( diff --git a/test/test_logging.cpp b/test/test_logging.cpp index d5196270..b45f13bf 100644 --- a/test/test_logging.cpp +++ b/test/test_logging.cpp @@ -88,7 +88,7 @@ TEST(CLASSNAME(TestLogging, RMW_IMPLEMENTATION), test_logging) { } EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_last_log_event.level); EXPECT_EQ("name1", g_last_log_event.name); - EXPECT_EQ("message 11", g_last_log_event.message); + EXPECT_EQ("[DEBUG] [name1]: message 11", g_last_log_event.message); // check default level int original_level = rcutils_logging_get_default_logger_level(); @@ -106,7 +106,7 @@ TEST(CLASSNAME(TestLogging, RMW_IMPLEMENTATION), test_logging) { EXPECT_EQ(2u, g_log_calls); EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level); EXPECT_EQ("name3", g_last_log_event.name); - EXPECT_EQ("message 33", g_last_log_event.message); + EXPECT_EQ("[INFO] [name3]: message 33", g_last_log_event.message); rcutils_log(NULL, RCUTILS_LOG_SEVERITY_WARN, "", ""); EXPECT_EQ(3u, g_log_calls); diff --git a/test/test_logging_macros.c b/test/test_logging_macros.c index eb9cdef7..3200effa 100644 --- a/test/test_logging_macros.c +++ b/test/test_logging_macros.c @@ -93,8 +93,8 @@ int main(int argc, char ** argv) fprintf(stderr, "name unexpectedly not empty string\n"); return 8; } - if (strcmp(g_last_log_event.message, "empty message")) { - fprintf(stderr, "message unexpectedly not 'empty message'\n"); + if (strcmp(g_last_log_event.message, "[INFO] []: empty message")) { + fprintf(stderr, "message unexpectedly not '[INFO] []: empty message'\n"); return 9; } @@ -123,8 +123,8 @@ int main(int argc, char ** argv) fprintf(stderr, "name unexpectedly not empty string\n"); return 15; } - if (strcmp(g_last_log_event.message, "message foo")) { - fprintf(stderr, "message unexpectedly not 'empty message'\n"); + if (strcmp(g_last_log_event.message, "[INFO] []: message foo")) { + fprintf(stderr, "message unexpectedly not '[INFO] []: message foo'\n"); return 16; } diff --git a/test/test_logging_macros.cpp b/test/test_logging_macros.cpp index 62bf5540..32cfb5af 100644 --- a/test/test_logging_macros.cpp +++ b/test/test_logging_macros.cpp @@ -89,7 +89,7 @@ TEST_F(TestLoggingMacros, test_logging_named) { } EXPECT_EQ(RCUTILS_LOG_SEVERITY_DEBUG, g_last_log_event.level); EXPECT_EQ("name", g_last_log_event.name); - EXPECT_EQ("message 3", g_last_log_event.message); + EXPECT_EQ("[DEBUG] [name]: message 3", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logging_once) { @@ -99,7 +99,7 @@ TEST_F(TestLoggingMacros, test_logging_once) { EXPECT_EQ(1u, g_log_calls); EXPECT_EQ(RCUTILS_LOG_SEVERITY_INFO, g_last_log_event.level); EXPECT_EQ("", g_last_log_event.name); - EXPECT_EQ("message 1", g_last_log_event.message); + EXPECT_EQ("[INFO] []: message 1", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logging_expression) { @@ -107,7 +107,7 @@ TEST_F(TestLoggingMacros, test_logging_expression) { RCUTILS_LOG_INFO_EXPRESSION(i % 3, "message %d", i); } EXPECT_EQ(4u, g_log_calls); - EXPECT_EQ("message 5", g_last_log_event.message); + EXPECT_EQ("[INFO] []: message 5", g_last_log_event.message); } int g_counter = 0; @@ -136,7 +136,7 @@ TEST_F(TestLoggingMacros, test_logging_function) { } EXPECT_EQ(4u, g_log_calls); EXPECT_TRUE(g_function_called); - EXPECT_EQ("message 5", g_last_log_event.message); + EXPECT_EQ("[INFO] []: message 5", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logging_skipfirst) { @@ -155,7 +155,7 @@ TEST_F(TestLoggingMacros, test_logging_throttle) { EXPECT_EQ(5u, g_log_calls); EXPECT_EQ(RCUTILS_LOG_SEVERITY_ERROR, g_last_log_event.level); EXPECT_EQ("", g_last_log_event.name); - EXPECT_EQ("throttled message 8", g_last_log_event.message); + EXPECT_EQ("[ERROR] []: throttled message 8", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logging_skipfirst_throttle) { @@ -168,7 +168,7 @@ TEST_F(TestLoggingMacros, test_logging_skipfirst_throttle) { EXPECT_EQ(4u, g_log_calls); EXPECT_EQ(RCUTILS_LOG_SEVERITY_FATAL, g_last_log_event.level); EXPECT_EQ("", g_last_log_event.name); - EXPECT_EQ("throttled message 8", g_last_log_event.message); + EXPECT_EQ("[FATAL] []: throttled message 8", g_last_log_event.message); } TEST_F(TestLoggingMacros, test_logger_hierarchy) {