roscpp overview: Initialization and Shutdown | Basics | Advanced: Traits [ROS C Turtle] | Advanced: Custom Allocators [ROS C Turtle] | Advanced: Serialization and Adapting Types [ROS C Turtle] | Publishers and Subscribers | Services | Parameter Server | Timers (Periodic Callbacks) | NodeHandles | Callbacks and Spinning | Logging | Names and Node Information | Time | Exceptions | Compilation Options | Advanced: Internals | tf/Overview | tf/Tutorials | C++ Style Guide

ROS has its own topic-based mechanism, called rosout for recording log messages from nodes. These log messages are human-readable string messages that convey the status of a node.

Viewing these statements in real-time is best done through the rqt_console GUI application (former rxconsole).

Log Statements

roscpp uses the rosconsole package to provide its client-side API. That API takes the form of a number of ROS_ macros:

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

rosconsole lets you disable or enable verbosity levels for specific packages and named loggers. For more information on the specifics of rosconsole, please see the rosconsole page.

The default verbosity level is INFO, so DEBUG statements will not be seen by default.

Output

There are four potential places a log message may end up, depending on the verbosity level:

stdout

  • DEBUG and INFO messages arrive on stdout if they are enabled. Note that this may not be sent to the screen depending on the value of the roslaunch/XML/node output parameter.

stderr

  • WARN, ERROR and FATAL messages arrive on stderr if they are enabled.

Node log file

  • Everything enabled goes into the log file. Your node's log file will be in ~/.ros/log unless you override it with the ROS_HOME or ROS_LOG_DIR environment variables. If you are using roslaunch, you can use the roslaunch-logs command to tell you the location of the log directory.

/rosout topic

  • Everything enabled is sent to the /rosout topic. Note that until the node is fully started, messages will not be sent, so you may not see initial messages.

Here is a table summarizing the above:

Debug

Info

Warn

Error

Fatal

stdout

X

X

stderr

X

X

X

log file

X

X

X

X

X

/rosout

X

X

X

X

X

Also note that this table is different for rospy.

Setting Verbosity Levels

There are three ways of setting verbosity levels on a roscpp node. The first is through a configuration file which sets the verbosity level for every node in the system, the second is at runtime through the rqt_logger_level (former rxloggerlevel) or rqt_console (former rxconsole) tools, and the third is programmatically through the rosconsole API:

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

See the rosconsole documentation for details.

Disable logging to /rosout

Broadcasting rosconsole output to the /rosout topic can be disabled with an Initialization Option or since roscpp 1.14.4 with the ROSCPP_NO_ROSOUT environment variable.

Wiki: roscpp/Overview/Logging (last edited 2020-02-25 10:18:02 by FelixRuess)