Show EOL distros: 

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

ROS console output library.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

ROS console output library.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

ROS console output library.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

ROS console output library.

ros_core: class_loader | cmake_modules | common_msgs | gencpp | geneus | genlisp | genmsg | gennodejs | genpy | message_generation | message_runtime | pluginlib | ros | ros_comm | rosbag_migration_rule | rosconsole | rosconsole_bridge | roscpp_core | rosgraph_msgs | roslisp | rospack | std_msgs | std_srvs

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

Package Summary

ROS console output library.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

ros_core: class_loader | cmake_modules | common_msgs | gencpp | geneus | genlisp | genmsg | gennodejs | genpy | message_generation | message_runtime | pluginlib | ros | ros_comm | rosbag_migration_rule | rosconsole | rosconsole_bridge | roscpp_core | rosgraph_msgs | roslisp | rospack | std_msgs | std_srvs

Package Summary

ROS console output library.

For documentation on console output and logging APIs for roscpp, please see the roscpp logging overview.

rosconsole is a C++ package that supports console output and logging in roscpp. It provides a macro-based interface which allows both printf- and stream-style output. It also wraps log4cxx, which supports hierarchical loggers, verbosity levels and configuration-files.

The requirements for rosconsole are:

  • Simple basic interface
  • No required explicit initialization step
  • Multiple severity level support: info/error/warning/debug/etc...
  • printf- and stream-style formatting

  • Ability to hook all output
  • Speed -- With output turned off, it should have minimal impact on runtime performance, preferably without recompilation
  • File and line information available per output statement
  • External configuration (environment or file based) of what level of output we want
  • Thread-safe
  • Ability to compile out debugging/low severity messages

rosconsole provides most of this through log4cxx, and implements a few of them through the macro wrappers.

rosconsole also provides an assertion/breakpoint library.

Code API

rosconsole provides eight different types of logging statements, at 5 different verbosity levels, with both printf- and stream-style formatting. Their name syntax is: ROS_<verbosity level>[_STREAM][_<other>]. For example, there are 5 versions of base printf- macro: ROS_DEBUG, ROS_INFO, ROS_WARN, ROS_ERROR and ROS_FATAL.

Note: the sections below only show examples for the DEBUG verbosity. Macros for the other verbosity levels follow the same pattern, just replace DEBUG with the appropriate level (ie: replace DEBUG with INFO for the INFO-level, etc).

  • Base

    • ROS_DEBUG(...)

    • ROS_DEBUG_STREAM(args)

    The base versions simply print an output message, ie:
    •    1 #include <ros/console.h>
         2 ROS_DEBUG("Hello %s", "World");
         3 ROS_DEBUG_STREAM("Hello " << "World");
      

    The base versions output to a logger named "ros.<your_package_name>".

  • Named

    • ROS_DEBUG_NAMED(name, ...)

    • ROS_DEBUG_STREAM_NAMED(name, args)

    The named versions output to a logger that is a child of the default one. This allows you to configure different logging statements to be enabled/disabled based on their name. For example:
    •    1 #include <ros/console.h>
         2 ROS_DEBUG_NAMED("test_only", "Hello %s", "World");
         3 ROS_DEBUG_STREAM_NAMED("test_only", "Hello " << "World");
      

    This will output to a logger named "ros.<your_package_name>.test_only". You can see the loggers using rqt_logger_level. More information about this is available in the configuration file section.

Do not use a variable with changing value as the name

Each named logger is stored in a static variable which is initialized on the use of the macro. Either use a string or a variable which string value is not going to change for future invocations since they won't be affecting the logger anymore.

  • Conditional

    • ROS_DEBUG_COND(cond, ...)

    • ROS_DEBUG_STREAM_COND(cond, args)

    The conditional versions will only output if the condition provided is true. The condition itself will only be evaluated if the logging statement itself is enabled.
    •    1 #include <ros/console.h>
         2 ROS_DEBUG_COND(x < 0, "Uh oh, x = %d, this is bad", x);
         3 ROS_DEBUG_STREAM_COND(x < 0, "Uh oh, x = " << x << ", this is bad");
      
  • Conditional Named

    • ROS_DEBUG_COND_NAMED(cond, name, ...)

    • ROS_DEBUG_STREAM_COND_NAMED(cond, name, args)

    The named conditional versions are just combinations of the above:
    •    1 #include <ros/console.h>
         2 ROS_DEBUG_COND_NAMED(x < 0, "test_only", "Uh oh, x = %d, this is bad", x);
         3 ROS_DEBUG_STREAM_COND_NAMED(x < 0, "test_only", "Uh oh, x = " << x << ", this is bad");
      
  • Once [1.1+]

    • ROS_DEBUG_ONCE(...)

    • ROS_DEBUG_STREAM_ONCE(args)

    • ROS_DEBUG_ONCE_NAMED(name, ...)

    • ROS_DEBUG_STREAM_ONCE_NAMED(name, args)

    These macros will only ever print out a warning the first time the macro is hit and enabled.
    •    1 #include <ros/console.h>
         2 for (int i = 0; i < 10; ++i)
         3 {
         4   ROS_DEBUG_ONCE("This message will only print once");
         5 }
      
  • Throttle [1.1+]

    • ROS_DEBUG_THROTTLE(period, ...)

    • ROS_DEBUG_STREAM_THROTTLE(period, args)

    • ROS_DEBUG_THROTTLE_NAMED(period, name, ...)

    • ROS_DEBUG_STREAM_THROTTLE_NAMED(period, name, args)

    Throttled output will print a message at most once per "period".
    •    1 while (true)
         2 {
         3   ROS_DEBUG_THROTTLE(60, "This message will print every 60 seconds");
         4 }
      
  • Delayed throttle (added in Indigo as of rosconsole version 1.11.11)

    • ROS_DEBUG_DELAYED_THROTTLE(period, ...)

    • ROS_DEBUG_STREAM_DELAYED_THROTTLE(period, args)

    • ROS_DEBUG_DELAYED_THROTTLE_NAMED(period, name, ...)

    • ROS_DEBUG_STREAM_DELAYED_THROTTLE_NAMED(period, name, args)

    Delayed throttled output will print a message at most once per "period" and no message will be printed before one "period" has elapsed.
    •    1 while (!ros::service::waitForService("add_two_ints", ros::Duration(0.1)) && ros::ok())
         2 {
         3   // This message will print every 10 seconds.
         4   // The macro will have no effect the first 10 seconds.
         5   // In other words, if the service is not available, the message will be
         6   // printed at times 10, 20, 30, ...
         7   ROS_DEBUG_DELAYED_THROTTLE(10, "Waiting for service 'add_two_ints'");
         8 }
      
  • Filter [1.1+]

    • ROS_DEBUG_FILTER(filter, ...)

    • ROS_DEBUG_STREAM_FILTER(filter, args)

    • ROS_DEBUG_FILTER_NAMED(filter, name, ...)

    • ROS_DEBUG_STREAM_FILTER_NAMED(filter, name, args)

    Filtered output allows you to specify a user-defined filter that extends the ros::console::FilterBase class. Your filter must be a pointer type.

The five different verbosity levels are, in order:

  • DEBUG
  • INFO
  • WARN
  • ERROR
  • FATAL

Assertions

rosconsole also provides assertions, in ros/assert.h:

  • ROS_ASSERT(cond)

  • ROS_ASSERT_MSG(cond, ...)

  • ROS_BREAK()

Configuration

rosconsole will load a config file from $ROS_ROOT/config/rosconsole.config when it initializes.

rosconsole also lets you define your own configuration file that will be used by log4cxx, defined by the ROSCONSOLE_CONFIG_FILE environment variable. Anything defined in this config file will override the default config file.

A simple example:

# Set the default ros output to warning and higher
log4j.logger.ros=WARN
# Override my package to output everything
log4j.logger.ros.my_package_name=DEBUG

You may have noticed that the example says "log4j" not "log4cxx". This is because log4cxx is directly compatible with log4j's configuration files.

ROS output is set to info and higher by default.

For more detailed information on the config file, and log4cxx in general, please see the official log4cxx documentation.

If you want to include a custom configuration into a specific launch file, you can do so using the <env>-tag of roslaunch.

Example:

<launch>
  <env name="ROSCONSOLE_CONFIG_FILE"
       value="$(find mypackage)/custom_rosconsole.conf"/>
  <node pkg="mypackage" type="mynode" name="mynode" output="screen"/>
</launch>

ROS Logger Hierarchy

Rosconsole uses the "ros" logger as its root-level logger. All unnamed logging statements will be output to the "ros.<package_name>" logger. The named variations will output to "ros.<package_name>.<name>". There are a couple of defines that expose this:

  • ROSCONSOLE_ROOT_LOGGER_NAME expands to "ros"

  • ROSCONSOLE_DEFAULT_NAME expands to "ros.<package_name>"

If you'd like to access one of your named loggers, you can get the name by:

   1 const char* logger_name = ROSCONSOLE_DEFAULT_NAME ".<name>"

Compile-time Logger Removal

rosconsole provides a way to remove logging at compile time, though this should rarely be necessary. This is accomplished through the ROSCONSOLE_MIN_SEVERITY define. Statements of a severity level lower than ROSCONSOLE_MIN_SEVERITY will be compiled out. The options are:

  • ROSCONSOLE_SEVERITY_DEBUG

  • ROSCONSOLE_SEVERITY_INFO

  • ROSCONSOLE_SEVERITY_WARN

  • ROSCONSOLE_SEVERITY_ERROR

  • ROSCONSOLE_SEVERITY_FATAL

  • ROSCONSOLE_SEVERITY_NONE (no logging will be compiled in)

Changing Logger Levels

If you want to change the logger levels via a configuration file, please see the Configuration section.

To change the logger levels from C++, use ros::console::set_logger_level(). Example:

#include <ros/console.h>
if( ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug) ) {
   ros::console::notifyLoggerLevelsChanged();
}

If you change one of the Logger's verbosity levels after any logging statements using that logger, you must call ros::console::notifyLoggerLevelsChanged(). If you do not, logging statements that have already been hit once (and therefore initialized) may continue to print when they should not, and vice-versa.

For examples of this behavior, please see the examples/example.cpp file.

Console Output Formatting

New in CTurtle

rosconsole allows you to specify how you'd like its output to show up in the console output through the ROSCONSOLE_FORMAT environment variable. The default is equivalent to:

export ROSCONSOLE_FORMAT='[${severity}] [${time}]: ${message}'

The full list of possible options follows.

Token

Sample Output

severity

ERROR

message

hello world 0

time

1284058208.824620563

(if no sim time is available it only shows the wall time)

1284058208.824620563, 1234567890.123456789

(if sim time is available it shows the wall time first and the sim time second)

walltime

1284058208.824620563

(this feature was always available in Python, in C++ it is only available since ros_console version 1.12.6)

thread

0xcd63d0

logger

ros.roscpp_tutorials

file

/wg/bvu/jfaust/ros/stacks/ros_tutorials/roscpp_tutorials/talker/talker.cpp

line

92

function

main

node

/talker

You can directly define the environment variable in a launch file (of course, change the value depending on your needs):

<launch>
  <env name="ROSCONSOLE_FORMAT" value="[${severity}] [${time}] [${node}]: ${message}"/>
  <node pkg="mypackage" type="mynode" name="mynode" output="screen"/>
</launch>

Change default time and walltime format

New in Noetic

It gives the user control over how dates and times can be represented.

You need to finish time or walltime token with colon and then specify format string, which can contain normal text together with argument specifiers like %M and %S. It looks like:

export ROSCONSOLE_FORMAT='${time:format string}'

or

export ROSCONSOLE_FORMAT='${walltime:format string}'

It mostly supports strfime specification for formatting dates/times.

The following table lists examples available for both C++ and Python.

Format Specifier

Example

%Y-%m-%d %H:%M:%S

2020-04-29 20:02:1

%y-%b-%d %I:%M:%S%p

20-Apr-29 08:20:40PM

%x %r

04/29/20 08:31:30 PM

Changed default value in Python

New in Kinetic as of rosconsole 1.12.6 the default format (if the environment variable is not set) for Python is now the same as for C++. If you want to keep the previous format for backward compatibility you can set the following:

export ROSCONSOLE_FORMAT='[${severity}] [WallTime: ${time}]: ${message}'

Disable all logging

With a configuration file

Create a custom rosconsole configuration file with the following content and use it as described above:

log4j.threshold=OFF

By calling a function

By invoking ros::console::shutdown(); in C++ the logging subsystem is shut down and therefore no more logging occurs.

Force line buffering for ROS logger

New in ROS Lunar

When stdout of a ROS application is fully buffered, for example in case when it is connected to a pipe, users may not see the output of the application until the buffer fills up. The user can force line buffering for ROS loggers that print to the console by setting the environment variable ROSCONSOLE_STDOUT_LINE_BUFFERED to 1.

export ROSCONSOLE_STDOUT_LINE_BUFFERED=1

In this case the buffer will be flushed after every line that is written to the logs.

Default value is 0. When set to 0 the flush is not triggered on every line and the default buffering scheme of stdout is used.

See also

Verbosity Level Best Practices

Wiki: rosconsole (last edited 2021-11-25 16:00:53 by LucasWalter)