Skip to content

Commit

Permalink
Publish logs to Rosout (#350)
Browse files Browse the repository at this point in the history
* Implementing the rosout logging feature.

* fixup for PR

* Fixup for PR.

* Fixing broken unit tests.

* Minor fixup for PR.

* Fixing bug in rosout teardown.

* Fixing unit test that broke because the rosout node wasn't getting counted.

* Fixing warnings on Windows.
  • Loading branch information
nburek authored and jacobperron committed Jan 14, 2019
1 parent ca97e5c commit c6788e4
Show file tree
Hide file tree
Showing 9 changed files with 519 additions and 49 deletions.
1 change: 1 addition & 0 deletions rcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ set(${PROJECT_NAME}_sources
src/rcl/init_options.c
src/rcl/lexer.c
src/rcl/lexer_lookahead.c
src/rcl/logging_rosout.c
src/rcl/logging.c
src/rcl/node.c
src/rcl/publisher.c
Expand Down
1 change: 1 addition & 0 deletions rcl/include/rcl/logging.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,6 +41,7 @@ extern "C"
* Lock-Free | Yes
*
* \param global_args The global arguments for the system
* \param allocator Used to allocate memory used by the logging 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
Expand Down
170 changes: 170 additions & 0 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,170 @@
// Copyright 2018-2019 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_ROSOUT_H_
#define RCL__LOGGING_ROSOUT_H_

#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcl/types.h"
#include "rcl/visibility_control.h"

#ifdef __cplusplus
extern "C"
{
#endif

/// Initializes the rcl_logging_rosout features
/**
* Calling this will initialize the rcl_logging_rosout features. This function must be called
* before any other rcl_logging_rosout_* functions can be called.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] allocator The allocator used for metadata related to the rcl_logging_rosout features
* \return `RCL_RET_OK` if the rcl_logging_rosout features are successfully initialized, or
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_init(
const rcl_allocator_t * allocator);

/// Uninitializes the rcl_logging_rosout features
/**
* Calling this will set the rcl_logging_rosout features into the an unitialized state that is
* functionally the same as before rcl_logging_rosout_init was called.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \return `RCL_RET_OK` if the rcl_logging_rosout feature was successfully unitialized, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_fini();

/// Creates a rosout publisher for a node and registers it to be used by the logging system
/**
* Calling this for an rcl_node_t will create a new publisher on that node that will be
* used by the logging system to publish all log messages from that Node's logger.
*
* If a publisher already exists for this node then a new publisher will NOT be created.
*
* It is expected that after creating a rosout publisher with this function
* rcl_logging_destroy_rosout_publisher_for_node() will be called for the node to cleanup
* the publisher while the Node is still valid.
*
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] node a valid rcl_node_t that the publisher will be created on
* \return `RCL_RET_OK` if the publisher was created successfully, or
* \return `RCL_RET_ALREADY_INIT` if the publisher has already exists, or
* \return `RCL_RET_NODE_INVALID` if any arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_init_publisher_for_node(
rcl_node_t * node);

/// Deregisters a rosout publisher for a node and cleans up allocated resources
/**
* Calling this for an rcl_node_t will destroy the rosout publisher on that node and remove it from
* the logging system so that no more Log messages are published to this function.
*
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] node a valid rcl_node_t that the publisher will be created on
* \return `RCL_RET_OK` if the publisher was created successfully, or
* \return `RCL_RET_NODE_INVALID` if any arguments are invalid, or
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_LOCAL
RCL_WARN_UNUSED
rcl_ret_t
rcl_logging_rosout_fini_publisher_for_node(
rcl_node_t * node);

/// The output handler outputs log messages to rosout topics.
/**
* When called with a logger name and log message this function will attempt to
* find a rosout publisher correlated with the logger name and publish a Log
* message out via that publisher. If there is no publisher directly correlated
* with the logger then nothing will be done.
*
* This function is meant to be registered with the logging functions for rcutils
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] location The pointer to the location struct or NULL
* \param[in] severity The severity level
* \param[in] name The name of the logger, must be null terminated c string
* \param[in] timestamp The timestamp for when the log message was made
* \param[in] log_str The string to be logged
*/
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);

#ifdef __cplusplus
}
#endif

#endif // RCL__LOGGING_ROSOUT_H_
1 change: 1 addition & 0 deletions rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@
<build_export_depend>rcutils</build_export_depend>
<build_export_depend>rosidl_generator_c</build_export_depend>

<exec_depend>rcl_interfaces</exec_depend>
<exec_depend>ament_cmake</exec_depend>
<exec_depend>rcutils</exec_depend>
<exec_depend>rosidl_default_runtime</exec_depend>
Expand Down
6 changes: 6 additions & 0 deletions rcl/src/rcl/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -174,6 +174,12 @@ rcl_shutdown(rcl_context_t * context)
return rcl_convert_rmw_ret_to_rcl_ret(rmw_ret);
}

rcl_ret_t rcl_ret = rcl_logging_fini();
RCUTILS_LOG_ERROR_EXPRESSION_NAMED(RCL_RET_OK != rcl_ret, ROS_PACKAGE_NAME,
"Failed to fini logging, rcl_ret_t: %i, rcl_error_str: %s", rcl_ret,
rcl_get_error_string().str);
rcl_reset_error();

return RCL_RET_OK;
}

Expand Down
63 changes: 29 additions & 34 deletions rcl/src/rcl/logging.c
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ extern "C"
#include "rcl/error_handling.h"
#include "rcl/logging.h"
#include "rcl/logging_external_interface.h"
#include "rcl/logging_rosout.h"
#include "rcl/macros.h"
#include "rcutils/logging.h"
#include "rcutils/time.h"
Expand All @@ -38,6 +39,9 @@ static rcutils_logging_output_handler_t

static uint8_t g_rcl_logging_num_out_handlers = 0;
static rcl_allocator_t g_logging_allocator;
static bool g_rcl_logging_stdout_enabled = false;
static bool g_rcl_logging_rosout_enabled = false;
static bool g_rcl_logging_ext_lib_enabled = false;

/**
* An output function that sends to multiple output appenders.
Expand All @@ -59,16 +63,6 @@ rcl_logging_ext_lib_output_handler(
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)
{
Expand All @@ -78,24 +72,27 @@ rcl_logging_configure(const rcl_arguments_t * global_args, const rcl_allocator_t
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;
g_rcl_logging_stdout_enabled = !global_args->impl->log_stdout_disabled;
g_rcl_logging_rosout_enabled = !global_args->impl->log_rosout_disabled;
g_rcl_logging_ext_lib_enabled = !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) {
if (g_rcl_logging_stdout_enabled) {
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 (g_rcl_logging_rosout_enabled) {
status = rcl_logging_rosout_init(allocator);
if (RCL_RET_OK == status) {
g_rcl_logging_out_handlers[g_rcl_logging_num_out_handlers++] =
rcl_logging_rosout_output_handler;
}
}
if (enable_ext_lib) {
if (g_rcl_logging_ext_lib_enabled) {
status = rcl_logging_external_initialize(config_file);
if (RCL_RET_OK == status) {
rcl_logging_external_set_logger_level(NULL, default_level);
Expand All @@ -107,6 +104,20 @@ rcl_logging_configure(const rcl_arguments_t * global_args, const rcl_allocator_t
return status;
}

rcl_ret_t rcl_logging_fini()
{
rcl_ret_t status = RCL_RET_OK;
rcutils_logging_set_output_handler(rcutils_logging_console_output_handler);

if (g_rcl_logging_rosout_enabled) {
status = rcl_logging_rosout_fini();
}
if (RCL_RET_OK == status && g_rcl_logging_ext_lib_enabled) {
status = rcl_logging_external_shutdown();
}

return status;
}

static
void
Expand Down Expand Up @@ -185,22 +196,6 @@ rcl_logging_ext_lib_output_handler(
}
}

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

0 comments on commit c6788e4

Please sign in to comment.