[Documentation] [TitleIndex] [WordIndex

ros_comm: cpp_common | message_filters | perf_roscpp | rosbag | rosbagmigration | rosconsole | roscore_migration_rules | roscpp | roscpp_serialization | roscpp_traits | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostime | rostopic | roswtf | std_msgs | std_srvs | topic_tools | xmlrpcpp

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:

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 four different types of logging statements, at 5 different verbosity levels, with both printf- and stream-style formatting.

  • 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");
         4 
      

    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");
         4 
      

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

  • 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");
         4 
      
  • 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");
         4 
      
  • 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 every 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 }
         6 
      
  • 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 }
         5 
      
  • 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:

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.

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:

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>"
   2 

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:

Changing Logger Levels

If you change one of the log4cxx::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

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

See also

Verbosity Level Best Practices


2011-11-19 12:33