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:
  . {{{#!cplusplus
#include <ros/console.h>
ROS_DEBUG("Hello %s", "World");
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:
  . {{{#!cplusplus
#include <ros/console.h>
ROS_DEBUG_NAMED("test_only", "Hello %s", "World");
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|rqt_logger_level]]. More information about this is available in the configuration file section.

{{{#!wiki caution
'''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.
  . {{{#!cplusplus
#include <ros/console.h>
ROS_DEBUG_COND(x < 0, "Uh oh, x = %d, this is bad", x);
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:
  . {{{#!cplusplus
#include <ros/console.h>
ROS_DEBUG_COND_NAMED(x < 0, "test_only", "Uh oh, x = %d, this is bad", x);
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.
  . {{{#!cplusplus
#include <ros/console.h>
for (int i = 0; i < 10; ++i)
{
  ROS_DEBUG_ONCE("This message will only print once");
}
}}}

 * '''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".
  . {{{#!cplusplus
while (true)
{
  ROS_DEBUG_THROTTLE(60, "This message will print every 60 seconds");
}
}}}

 * '''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.
  . {{{#!cplusplus
while (!ros::service::waitForService("add_two_ints", ros::Duration(0.1)) && ros::ok())
{
  // This message will print every 10 seconds.
  // The macro will have no effect the first 10 seconds.
  // In other words, if the service is not available, the message will be
  // printed at times 10, 20, 30, ...
  ROS_DEBUG_DELAYED_THROTTLE(10, "Waiting for service 'add_two_ints'");
}
}}}

 * '''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 [[http://docs.ros.org/api/rosconsole/html/classros_1_1console_1_1FilterBase.html|ros::console::FilterBase]] class.  Your filter must be a pointer type.

The five different [[Verbosity Levels|verbosity levels]] are, in order:

 * DEBUG
 * INFO
 * WARN
 * ERROR
 * FATAL