Adding new cli parameters for configuring the logging. (#327)
* Adding new cli parameters for configuring the logging. cr https://code.amazon.com/reviews/CR-3728503 * Moving the external logger library from rcutils into rcl. Also automatic uncrustify. * Fixing issue with rebase * Temporarily switching the default to noop logger ext_lib while system dependency issue is solved for Windows/Mac. * Fixing the format2/3 xmllint issue. * style changes, and one actual fix Signed-off-by: William Woodall <william@osrfoundation.org> * rename rc_logging* to rcl_logging* Signed-off-by: William Woodall <william@osrfoundation.org> * Expand rcl_logging_configure API with allocator This is to make sure that this API is complete, and we can merge rcl#350 later without breaking the API at a later date. * update logging.c with new use of allocator in API * update init.c with new API changes * Switching back to va_list for output handlers. * address review comments Signed-off-by: William Woodall <william@osrfoundation.org>
This commit is contained in:
parent
66b82291a1
commit
228cd0082c
11 changed files with 611 additions and 9 deletions
|
@ -12,6 +12,9 @@ find_package(rosidl_generator_c REQUIRED)
|
|||
|
||||
include_directories(include)
|
||||
|
||||
include(cmake/get_default_rcl_logging_implementation.cmake)
|
||||
get_default_rcl_logging_implementation(RCL_LOGGING_IMPL)
|
||||
|
||||
# Default to C11
|
||||
if(NOT CMAKE_C_STANDARD)
|
||||
set(CMAKE_C_STANDARD 11)
|
||||
|
@ -38,6 +41,7 @@ set(${PROJECT_NAME}_sources
|
|||
src/rcl/init_options.c
|
||||
src/rcl/lexer.c
|
||||
src/rcl/lexer_lookahead.c
|
||||
src/rcl/logging.c
|
||||
src/rcl/node.c
|
||||
src/rcl/publisher.c
|
||||
src/rcl/remap.c
|
||||
|
@ -58,6 +62,7 @@ ament_target_dependencies(${PROJECT_NAME}
|
|||
"rmw"
|
||||
"rcutils"
|
||||
"rosidl_generator_c"
|
||||
${RCL_LOGGING_IMPL}
|
||||
)
|
||||
|
||||
# Causes the visibility macros to use dllexport rather than dllimport,
|
||||
|
@ -86,6 +91,7 @@ ament_export_dependencies(rmw_implementation)
|
|||
ament_export_dependencies(rmw)
|
||||
ament_export_dependencies(rcutils)
|
||||
ament_export_dependencies(rosidl_generator_c)
|
||||
ament_export_dependencies(${RCL_LOGGING_IMPL})
|
||||
|
||||
if(BUILD_TESTING)
|
||||
find_package(ament_lint_auto REQUIRED)
|
||||
|
|
46
rcl/cmake/get_default_rcl_logging_implementation.cmake
Normal file
46
rcl/cmake/get_default_rcl_logging_implementation.cmake
Normal file
|
@ -0,0 +1,46 @@
|
|||
# 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 RCL_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_rcl_logging_implementation var)
|
||||
|
||||
# if logging implementation already specified or RCL_LOGGING_IMPLEMENTATION environment variable
|
||||
# is set then use that, otherwise default to using rcl_logging_noop
|
||||
if(NOT "${RCL_LOGGING_IMPLEMENTATION}" STREQUAL "")
|
||||
set(_logging_implementation "${RCL_LOGGING_IMPLEMENTATION}")
|
||||
elseif(NOT "$ENV{RCL_LOGGING_IMPLEMENTATION}" STREQUAL "")
|
||||
set(_logging_implementation "$ENV{RCL_LOGGING_IMPLEMENTATION}")
|
||||
else()
|
||||
set(_logging_implementation rcl_logging_noop)
|
||||
endif()
|
||||
|
||||
# persist implementation decision in cache
|
||||
# if it was not determined dynamically
|
||||
set(
|
||||
RCL_LOGGING_IMPLEMENTATION "${_logging_implementation}"
|
||||
CACHE STRING "select rcl logging implementation to use" FORCE
|
||||
)
|
||||
|
||||
find_package("${_logging_implementation}" REQUIRED)
|
||||
|
||||
set(${var} ${_logging_implementation})
|
||||
endmacro()
|
|
@ -35,6 +35,10 @@ typedef struct rcl_arguments_t
|
|||
} rcl_arguments_t;
|
||||
|
||||
#define RCL_LOG_LEVEL_ARG_RULE "__log_level:="
|
||||
#define RCL_EXTERNAL_LOG_CONFIG_ARG_RULE "__log_config_file:="
|
||||
#define RCL_LOG_DISABLE_STDOUT_ARG_RULE "__log_disable_stdout:="
|
||||
#define RCL_LOG_DISABLE_ROSOUT_ARG_RULE "__log_disable_rosout:="
|
||||
#define RCL_LOG_DISABLE_EXT_LIB_ARG_RULE "__log_disable_external_lib:="
|
||||
#define RCL_PARAM_FILE_ARG_RULE "__params:="
|
||||
|
||||
/// Return a rcl_node_t struct with members initialized to `NULL`.
|
||||
|
|
77
rcl/include/rcl/logging.h
Normal file
77
rcl/include/rcl/logging.h
Normal file
|
@ -0,0 +1,77 @@
|
|||
// 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 RCL__LOGGING_H_
|
||||
#define RCL__LOGGING_H_
|
||||
|
||||
#include "rcl/allocator.h"
|
||||
#include "rcl/arguments.h"
|
||||
#include "rcl/macros.h"
|
||||
#include "rcl/types.h"
|
||||
#include "rcl/visibility_control.h"
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
|
||||
/// Configure 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.
|
||||
*
|
||||
* <hr>
|
||||
* Attribute | Adherence
|
||||
* ------------------ | -------------
|
||||
* Allocates Memory | Yes
|
||||
* Thread-Safe | No
|
||||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \param global_args The global arguments for the system
|
||||
* \return `RCL_RET_OK` if successful, or
|
||||
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||
* \return `RCL_RET_ERR` if a general error occurs
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_logging_configure(
|
||||
const rcl_arguments_t * global_args,
|
||||
const rcl_allocator_t * allocator);
|
||||
|
||||
/**
|
||||
* This function should be called to tear down the logging setup by the configure function.
|
||||
*
|
||||
* <hr>
|
||||
* Attribute | Adherence
|
||||
* ------------------ | -------------
|
||||
* Allocates Memory | No
|
||||
* Thread-Safe | No
|
||||
* Uses Atomics | No
|
||||
* Lock-Free | Yes
|
||||
*
|
||||
* \return `RCL_RET_OK` if successful.
|
||||
* \return `RCL_RET_ERR` if a general error occurs
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t rcl_logging_fini();
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
||||
#endif // RCL__LOGGING_H_
|
75
rcl/include/rcl/logging_external_interface.h
Normal file
75
rcl/include/rcl/logging_external_interface.h
Normal file
|
@ -0,0 +1,75 @@
|
|||
// 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 RCL__LOGGING_EXTERNAL_INTERFACE_H_
|
||||
#define RCL__LOGGING_EXTERNAL_INTERFACE_H_
|
||||
|
||||
#include "rcl/macros.h"
|
||||
#include "rcl/types.h"
|
||||
#include "rcl/visibility_control.h"
|
||||
|
||||
/// Initialize the external logging library.
|
||||
/**
|
||||
* \param[in] 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 RCL_RET_OK if initialized successfully, or
|
||||
* \return RCL_RET_ERROR if an unspecified error occurs.
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_logging_external_initialize(const char * config_file);
|
||||
|
||||
/// Free the resources allocated for the external logging system.
|
||||
/**
|
||||
* This puts the system into a state equivalent to being uninitialized.
|
||||
*
|
||||
* \return RCL_RET_OK if successfully shutdown, or
|
||||
* \return RCL_RET_ERROR if an unspecified error occurs.
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_logging_external_shutdown();
|
||||
|
||||
/// Log a message.
|
||||
/**
|
||||
* \param[in] severity The severity level of the message being logged.
|
||||
* \param[in] name The name of the logger, must either be a null terminated
|
||||
* c string or NULL.
|
||||
* If NULL or empty the root logger will be used.
|
||||
* \param[in] msg The message to be logged. Must be a null terminated c string.
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
void
|
||||
rcl_logging_external_log(int severity, const char * name, const char * msg);
|
||||
|
||||
/// Set the severity level for a logger.
|
||||
/**
|
||||
* This function 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[in] name The name of the logger.
|
||||
* Must be a NULL terminated c string or NULL.
|
||||
* \param[in] level The severity level to be used for the specified logger.
|
||||
* \return RCL_RET_OK if set successfully, or
|
||||
* \return RCL_RET_ERROR if an unspecified error occurs.
|
||||
*/
|
||||
RCL_PUBLIC
|
||||
rcl_ret_t rcl_logging_external_set_logger_level(const char * name, int level);
|
||||
|
||||
#endif // RCL__LOGGING_EXTERNAL_INTERFACE_H_
|
|
@ -27,6 +27,8 @@ extern "C"
|
|||
# define RCL_WARN_UNUSED _Check_return_
|
||||
#endif
|
||||
|
||||
#define RCL_UNUSED(x) (void)(x)
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
<?xml version="1.0"?>
|
||||
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="2">
|
||||
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||
<package format="3">
|
||||
<name>rcl</name>
|
||||
<version>0.6.0</version>
|
||||
<description>The ROS client library common implementation.
|
||||
|
@ -37,6 +37,8 @@
|
|||
<test_depend>osrf_testing_tools_cpp</test_depend>
|
||||
<test_depend>test_msgs</test_depend>
|
||||
|
||||
<group_depend>rcl_logging_packages</group_depend>
|
||||
|
||||
<export>
|
||||
<build_type>ament_cmake</build_type>
|
||||
</export>
|
||||
|
|
|
@ -25,6 +25,7 @@
|
|||
#include "rcl/validate_topic_name.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"
|
||||
|
@ -131,6 +132,56 @@ _rcl_parse_log_level_rule(
|
|||
rcl_allocator_t allocator,
|
||||
int * log_level);
|
||||
|
||||
/// Parse an argument that may or may not be a log file rule.
|
||||
/**
|
||||
* \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 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_bool_arg(
|
||||
const char * arg,
|
||||
const char * key,
|
||||
bool * value);
|
||||
|
||||
/// Parse a null terminated string to a boolean value.
|
||||
/**
|
||||
* The case sensitive values: "T", "t", "True", "true", "Y", "y", "Yes", "yes",
|
||||
* and "1" will all map to true.
|
||||
* The case sensitive values: "F", "f", "False", "false", "N", "n", "No", "no",
|
||||
* and "0" will all map to false.
|
||||
*
|
||||
* \param[in] str a null terminated string to be parsed into a boolean
|
||||
* \param[in,out] val the boolean value parsed from the string.
|
||||
* Left unchanged if string cannot be parsed to a valid bool.
|
||||
* \return RCL_RET_OK if a valid boolean parsed, or
|
||||
* \return RLC_RET_ERROR if an unspecified error occurred.
|
||||
*/
|
||||
RCL_LOCAL
|
||||
rcl_ret_t
|
||||
_atob(
|
||||
const char * str,
|
||||
bool * val);
|
||||
|
||||
rcl_ret_t
|
||||
rcl_parse_arguments(
|
||||
int argc,
|
||||
|
@ -163,10 +214,14 @@ rcl_parse_arguments(
|
|||
args_impl->num_remap_rules = 0;
|
||||
args_impl->remap_rules = NULL;
|
||||
args_impl->log_level = -1;
|
||||
args_impl->external_log_config_file = NULL;
|
||||
args_impl->unparsed_args = NULL;
|
||||
args_impl->num_unparsed_args = 0;
|
||||
args_impl->parameter_files = NULL;
|
||||
args_impl->num_param_files_args = 0;
|
||||
args_impl->log_stdout_disabled = false;
|
||||
args_impl->log_rosout_disabled = false;
|
||||
args_impl->log_ext_lib_disabled = false;
|
||||
args_impl->allocator = allocator;
|
||||
|
||||
if (argc == 0) {
|
||||
|
@ -207,7 +262,7 @@ rcl_parse_arguments(
|
|||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as parameter file rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string());
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as remap rule
|
||||
|
@ -218,7 +273,8 @@ rcl_parse_arguments(
|
|||
continue;
|
||||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as remap rule. Error: %s", i, argv[i], rcl_get_error_string());
|
||||
"Couldn't parse arg %d (%s) as remap rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as log level configuration
|
||||
|
@ -229,9 +285,54 @@ rcl_parse_arguments(
|
|||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as log level rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string());
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as log configuration file
|
||||
rcl_ret_t ret = _rcl_parse_external_log_config_file(
|
||||
argv[i], allocator, &args_impl->external_log_config_file);
|
||||
if (RCL_RET_OK == ret) {
|
||||
continue;
|
||||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as log config rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as log_stdout_disabled
|
||||
ret = _rcl_parse_bool_arg(
|
||||
argv[i], RCL_LOG_DISABLE_STDOUT_ARG_RULE, &args_impl->log_stdout_disabled);
|
||||
if (RCL_RET_OK == ret) {
|
||||
continue;
|
||||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as log_stdout_disabled rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as log_rosout_disabled
|
||||
ret = _rcl_parse_bool_arg(
|
||||
argv[i], RCL_LOG_DISABLE_ROSOUT_ARG_RULE, &args_impl->log_rosout_disabled);
|
||||
if (RCL_RET_OK == ret) {
|
||||
continue;
|
||||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as log_rosout_disabled rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
// Attempt to parse argument as log_ext_lib_disabled
|
||||
ret = _rcl_parse_bool_arg(
|
||||
argv[i], RCL_LOG_DISABLE_EXT_LIB_ARG_RULE, &args_impl->log_ext_lib_disabled);
|
||||
if (RCL_RET_OK == ret) {
|
||||
continue;
|
||||
}
|
||||
RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME,
|
||||
"Couldn't parse arg %d (%s) as log_ext_lib_disabled rule. Error: %s", i, argv[i],
|
||||
rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
|
||||
|
||||
// Argument wasn't parsed by any rule
|
||||
args_impl->unparsed_args[args_impl->num_unparsed_args] = i;
|
||||
++(args_impl->num_unparsed_args);
|
||||
|
@ -1053,7 +1154,7 @@ _rcl_parse_param_file_rule(
|
|||
size_t outlen = strlen(arg) - param_prefix_len;
|
||||
*param_file = allocator.allocate(sizeof(char) * (outlen + 1), allocator.state);
|
||||
if (NULL == *param_file) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to allocate memory for parameters file path\n");
|
||||
RCL_SET_ERROR_MSG("Failed to allocate memory for parameters file path");
|
||||
return RCL_RET_BAD_ALLOC;
|
||||
}
|
||||
snprintf(*param_file, outlen + 1, "%s", arg + param_prefix_len);
|
||||
|
@ -1063,6 +1164,77 @@ _rcl_parse_param_file_rule(
|
|||
return RCL_RET_INVALID_PARAM_RULE;
|
||||
}
|
||||
|
||||
rcl_ret_t
|
||||
_rcl_parse_external_log_config_file(
|
||||
const char * arg,
|
||||
rcl_allocator_t allocator,
|
||||
char ** log_config_file)
|
||||
{
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(log_config_file, RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
const size_t param_prefix_len = sizeof(RCL_EXTERNAL_LOG_CONFIG_ARG_RULE) - 1;
|
||||
if (strncmp(RCL_EXTERNAL_LOG_CONFIG_ARG_RULE, arg, param_prefix_len) == 0) {
|
||||
size_t outlen = strlen(arg) - param_prefix_len;
|
||||
*log_config_file = rcutils_format_string_limit(allocator, outlen, "%s", arg + param_prefix_len);
|
||||
if (NULL == *log_config_file) {
|
||||
RCL_SET_ERROR_MSG("Failed to allocate memory for external log config file");
|
||||
return RCL_RET_BAD_ALLOC;
|
||||
}
|
||||
return RCL_RET_OK;
|
||||
}
|
||||
|
||||
RCL_SET_ERROR_MSG("Argument does not start with '" RCL_EXTERNAL_LOG_CONFIG_ARG_RULE "'");
|
||||
return RCL_RET_INVALID_PARAM_RULE;
|
||||
}
|
||||
|
||||
RCL_LOCAL
|
||||
rcl_ret_t
|
||||
_rcl_parse_bool_arg(
|
||||
const char * arg,
|
||||
const char * key,
|
||||
bool * value)
|
||||
{
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(arg, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(key, RCL_RET_INVALID_ARGUMENT);
|
||||
|
||||
const size_t param_prefix_len = strlen(key);
|
||||
if (strncmp(key, arg, param_prefix_len) == 0) {
|
||||
return _atob(arg + param_prefix_len, value);
|
||||
}
|
||||
|
||||
RCL_SET_ERROR_MSG("Argument does not start with key");
|
||||
return RCL_RET_INVALID_PARAM_RULE;
|
||||
}
|
||||
|
||||
RCL_LOCAL
|
||||
rcl_ret_t
|
||||
_atob(
|
||||
const char * str,
|
||||
bool * val)
|
||||
{
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(str, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(val, RCL_RET_INVALID_ARGUMENT);
|
||||
const char * true_values[] = {"y", "Y", "yes", "Yes", "t", "T", "true", "True", "1"};
|
||||
const char * false_values[] = {"n", "N", "no", "No", "f", "F", "false", "False", "0"};
|
||||
|
||||
for (size_t idx = 0; idx < sizeof(true_values) / sizeof(char *); idx++) {
|
||||
if (0 == strncmp(true_values[idx], str, strlen(true_values[idx]))) {
|
||||
*val = true;
|
||||
return RCL_RET_OK;
|
||||
}
|
||||
}
|
||||
|
||||
for (size_t idx = 0; idx < sizeof(false_values) / sizeof(char *); idx++) {
|
||||
if (0 == strncmp(false_values[idx], str, strlen(false_values[idx]))) {
|
||||
*val = false;
|
||||
return RCL_RET_OK;
|
||||
}
|
||||
}
|
||||
|
||||
return RCL_RET_ERROR;
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -44,6 +44,14 @@ typedef struct rcl_arguments_impl_t
|
|||
|
||||
/// Default log level (represented by `RCUTILS_LOG_SEVERITY` enum) or -1 if not specified.
|
||||
int log_level;
|
||||
/// A file used to configure the external logging library
|
||||
char * external_log_config_file;
|
||||
/// A boolean value indicating if the standard out handler should be used for log output
|
||||
bool log_stdout_disabled;
|
||||
/// A boolean value indicating if the rosout topic handler should be used for log output
|
||||
bool log_rosout_disabled;
|
||||
/// A boolean value indicating if the external lib handler should be used for log output
|
||||
bool log_ext_lib_disabled;
|
||||
|
||||
/// Allocator used to allocate objects in this struct
|
||||
rcl_allocator_t allocator;
|
||||
|
|
|
@ -25,6 +25,7 @@ extern "C"
|
|||
#include "./init_options_impl.h"
|
||||
#include "rcl/arguments.h"
|
||||
#include "rcl/error_handling.h"
|
||||
#include "rcl/logging.h"
|
||||
#include "rcutils/logging_macros.h"
|
||||
#include "rcutils/stdatomic_helper.h"
|
||||
#include "rmw/error_handling.h"
|
||||
|
@ -110,9 +111,12 @@ rcl_init(
|
|||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to parse global arguments");
|
||||
goto fail;
|
||||
}
|
||||
// Update the default log level if specified in arguments.
|
||||
if (context->global_arguments.impl->log_level >= 0) {
|
||||
rcutils_logging_set_default_logger_level(context->global_arguments.impl->log_level);
|
||||
|
||||
ret = rcl_logging_configure(&context->global_arguments, &allocator);
|
||||
if (RCL_RET_OK != ret) {
|
||||
fail_ret = ret;
|
||||
RCUTILS_LOG_ERROR_NAMED(ROS_PACKAGE_NAME, "Failed to configure logging. %i", fail_ret);
|
||||
goto fail;
|
||||
}
|
||||
|
||||
// Set the instance id.
|
||||
|
|
206
rcl/src/rcl/logging.c
Normal file
206
rcl/src/rcl/logging.c
Normal file
|
@ -0,0 +1,206 @@
|
|||
// 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.
|
||||
|
||||
#ifdef __cplusplus
|
||||
extern "C"
|
||||
{
|
||||
#endif
|
||||
|
||||
#include <ctype.h>
|
||||
#include <inttypes.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "./arguments_impl.h"
|
||||
#include "rcl/allocator.h"
|
||||
#include "rcl/error_handling.h"
|
||||
#include "rcl/logging.h"
|
||||
#include "rcl/logging_external_interface.h"
|
||||
#include "rcl/macros.h"
|
||||
#include "rcutils/logging.h"
|
||||
#include "rcutils/time.h"
|
||||
|
||||
#define RCL_LOGGING_MAX_OUTPUT_FUNCS (4)
|
||||
|
||||
static rcutils_logging_output_handler_t
|
||||
g_rcl_logging_out_handlers[RCL_LOGGING_MAX_OUTPUT_FUNCS] = {0};
|
||||
|
||||
static uint8_t g_rcl_logging_num_out_handlers = 0;
|
||||
static rcl_allocator_t g_logging_allocator;
|
||||
|
||||
/**
|
||||
* An output function that sends to multiple output appenders.
|
||||
*/
|
||||
static
|
||||
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);
|
||||
|
||||
/**
|
||||
* An output function that sends to the external logger library.
|
||||
*/
|
||||
static
|
||||
void
|
||||
rcl_logging_ext_lib_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);
|
||||
|
||||
/**
|
||||
* An output function that sends to the rosout topic.
|
||||
*/
|
||||
static
|
||||
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);
|
||||
|
||||
rcl_ret_t
|
||||
rcl_logging_configure(const rcl_arguments_t * global_args, const rcl_allocator_t * allocator)
|
||||
{
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(global_args, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(allocator, RCL_RET_INVALID_ARGUMENT);
|
||||
RCUTILS_LOGGING_AUTOINIT
|
||||
g_logging_allocator = *allocator;
|
||||
int default_level = global_args->impl->log_level;
|
||||
const char * config_file = global_args->impl->external_log_config_file;
|
||||
bool enable_stdout = !global_args->impl->log_stdout_disabled;
|
||||
bool enable_rosout = !global_args->impl->log_rosout_disabled;
|
||||
bool enable_ext_lib = !global_args->impl->log_ext_lib_disabled;
|
||||
rcl_ret_t status = RCL_RET_OK;
|
||||
g_rcl_logging_num_out_handlers = 0;
|
||||
|
||||
if (default_level >= 0) {
|
||||
rcutils_logging_set_default_logger_level(default_level);
|
||||
}
|
||||
if (enable_stdout) {
|
||||
g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
|
||||
rcutils_logging_console_output_handler;
|
||||
}
|
||||
if (enable_rosout) {
|
||||
g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
|
||||
rcl_logging_rosout_output_handler;
|
||||
}
|
||||
if (enable_ext_lib) {
|
||||
status = rcl_logging_external_initialize(config_file);
|
||||
if (RCL_RET_OK == status) {
|
||||
rcl_logging_external_set_logger_level(NULL, default_level);
|
||||
g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
|
||||
rcl_logging_ext_lib_output_handler;
|
||||
}
|
||||
}
|
||||
rcutils_logging_set_output_handler(rcl_logging_multiple_output_handler);
|
||||
return status;
|
||||
}
|
||||
|
||||
|
||||
static
|
||||
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)
|
||||
{
|
||||
for (uint8_t i = 0;
|
||||
i < g_rcl_logging_num_out_handlers && NULL != g_rcl_logging_out_handlers[i]; ++i)
|
||||
{
|
||||
g_rcl_logging_out_handlers[i](location, severity, name, timestamp, format, args);
|
||||
}
|
||||
}
|
||||
|
||||
static
|
||||
void
|
||||
rcl_logging_ext_lib_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)
|
||||
{
|
||||
rcl_ret_t status;
|
||||
char msg_buf[1024] = "";
|
||||
rcutils_char_array_t msg_array = {
|
||||
.buffer = msg_buf,
|
||||
.owns_buffer = false,
|
||||
.buffer_length = 0u,
|
||||
.buffer_capacity = sizeof(msg_buf),
|
||||
.allocator = g_logging_allocator
|
||||
};
|
||||
|
||||
char output_buf[1024] = "";
|
||||
rcutils_char_array_t output_array = {
|
||||
.buffer = output_buf,
|
||||
.owns_buffer = false,
|
||||
.buffer_length = 0u,
|
||||
.buffer_capacity = sizeof(output_buf),
|
||||
.allocator = g_logging_allocator
|
||||
};
|
||||
|
||||
va_list args_clone;
|
||||
va_copy(args_clone, *args);
|
||||
status = rcutils_char_array_vsprintf(&msg_array, format, args_clone);
|
||||
va_end(args_clone);
|
||||
|
||||
if (RCL_RET_OK == status) {
|
||||
status = rcutils_logging_format_message(
|
||||
location, severity, name, timestamp, msg_array.buffer, &output_array);
|
||||
if (RCL_RET_OK != status) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to format log message: ");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||
}
|
||||
} else {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to format user log message: ");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||
}
|
||||
rcl_logging_external_log(severity, name, output_array.buffer);
|
||||
status = rcutils_char_array_fini(&msg_array);
|
||||
if (RCL_RET_OK != status) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to finalize char array: ");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||
}
|
||||
status = rcutils_char_array_fini(&output_array);
|
||||
if (RCL_RET_OK != status) {
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("failed to finalize char array: ");
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
|
||||
rcl_reset_error();
|
||||
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
|
||||
}
|
||||
}
|
||||
|
||||
static
|
||||
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)
|
||||
{
|
||||
// TODO(nburek): Placeholder for rosout topic feature
|
||||
RCL_UNUSED(location);
|
||||
RCL_UNUSED(severity);
|
||||
RCL_UNUSED(name);
|
||||
RCL_UNUSED(timestamp);
|
||||
RCL_UNUSED(format);
|
||||
RCL_UNUSED(args);
|
||||
}
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
Loading…
Add table
Add a link
Reference in a new issue