Package Proposal

Rosconsole is a drop-in replacement for simple console/terminal output that would normally go through printf. All output from ROS packages would be required to go through this package, allowing it to be routed however we want (logs, rosout, etc.).

Requirements

  • Simple basic interface
  • No required explicit initialization step
  • Multiple severity level support -- info/error/warning/debug/etc.
  • Printf-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

Implementation/API

I looked at a number of different open-source logging packages to determine if any of them meet our needs. In the end, RLog (http://www.arg0.net/rlog) and log4cxx (http://logging.apache.org/log4cxx/index.html) were the only ones I considered worth a more detailed look. RLog is notable for its speed when turned off, log4cxx for its feature set. Without looking at speed, log4cxx is the hands-down winner (mostly because of its configuration support). After some speed tests (detailed below), I have concluded that log4cxx is fast enough. The other logging packages I looked at, along with the reason for not seriously considering them, are also detailed below.

I propose we implement a light wrapper on top of log4cxx. Log4cxx is a very powerful, feature-rich logging library developed by the Apache foundation. Log4cxx natively supports most of our requirements:

  • Simple basic interface
  • Multiple severity level support
  • Hook all output -- through "Appenders"
  • Speed -- messages sent that are below the logger/global threshold are quickly rejected
  • File and line information provided to the appender
  • External configuration -- excellent config file support (identical to log4j)
  • Thread-safe

There are a few requirements that log4cxx does not support natively, but that we can easily add in our wrapper:

  • No required explicit initialization step -- we can auto-initialize through our own calls. Anyone wanting to use log4cxx directly should initialize rosconsole first
  • Printf-style formatting -- easy to add through our wrappers (sample below)
  • Ability to compile out debugging/low severity messages -- again, easy to add to our wrapper (though not implemented in the sample interface below)

Wrapping log4cxx instead of using it directly allows us to easily customize it to our needs, and replace it if necessary.

Here's an example of what the usage would be:

#include "rosconsole.h"

int main(int argc, char** argv)
{
  ROS_INFO( "Info %s", "World" );
  ROS_ERROR( "Error %s", "World" );
  ROS_WARNING( "Warning %s", "World" );
  ROS_DEBUG( "Debug %s", "World" );
}

And an example of what the basic public interface could look like:

namespace ros
{
  namespace console
  {
    extern bool g_initialized;
    extern ros::thread::mutex g_init_mutex;
    extern log4cxx::LoggerPtr g_logger;

    void print( const log4cxx::LevelPtr& level, const char* file, const int line, const char* fmt, ... );
  }
}

#define ROS_INFO(...)     \
  do                      \
  {                       \
    ROSCONSOLE_AUTOINIT;                 \
    if ( ros::console::g_logger->isInfoEnabled() )                      \
    {                                                                   \
      ros::console::print( log4cxx::Level::INFO, __FILE__, __LINE__, __VA_ARGS__); \
    }                                                                   \
  } while(0)


  
#define ROS_WARNING(...)                 \
  do                                     \
    {                                    \
    ROSCONSOLE_AUTOINIT;                 \
    if ( ros::console::g_logger->isWarnEnabled() )\
    {                                                                   \
      ros::console::print( log4cxx::Level::WARN, __FILE__, __LINE__, __VA_ARGS__); \
    }                                                                   \
  } while(0)

#define ROS_ERROR(...)     \
  do                      \
  {                       \
    ROSCONSOLE_AUTOINIT;                 \
    if ( ros::console::g_logger->isErrorEnabled() )                     \
    {                                                                   \
      ros::console::print( log4cxx::Level::ERROR, __FILE__, __LINE__, __VA_ARGS__); \
    }                                                                   \
  } while(0)

#define ROS_DEBUG(...)     \
  do                      \
  {                       \
    ROSCONSOLE_AUTOINIT;                 \
    if ( ros::console::g_logger->isDebugEnabled() )                     \
    {                                                                   \
      ros::console::print( log4cxx::Level::DEBUG, __FILE__, __LINE__, __VA_ARGS__); \
    }                                                                   \
  } while(0)

#define ROS_FATAL(...)     \
  do                      \
  {                       \
    ROSCONSOLE_AUTOINIT;                 \
    if ( ros::console::g_logger->isFatalEnabled() )                     \
    {                                                                   \
      ros::console::print( log4cxx::Level::FATAL, __FILE__, __LINE__, __VA_ARGS__); \
    }                                                                   \
  } while(0)

Speed comparison, RLog vs. log4cxx

For the speed test I implemented two versions of "rosconsole", one which used rlog, and one which used log4cxx. I then wrote a python script that would generate code calling into rosconsole:

import sys

f = open('rosconsole_test_generated.cpp', 'w')

for i in range(0,int(sys.argv[1])):
    f.write('void info%s(int i) { ROS_INFO("Info%s: %%d", i); }\n' %(i,i))
    f.write('void warn%s(int i) { ROS_WARNING("Warn%s: %%d", i); }\n' %(i,i))
    f.write('void error%s(int i) { ROS_ERROR("Error%s: %%d", i); }\n' %(i,i))
    f.write('void debug%s(int i) { ROS_DEBUG("Debug%s: %%d", i); }\n' %(i,i))
    f.write('void fatal%s(int i) { ROS_FATAL("Fatal%s: %%d", i); }\n' %(i,i))

f.write('int main(int argc, char** argv)\n{\n')
f.write('for (int i = 0;i < %s; ++i)\n{\n' %(sys.argv[2]))

for i in range(0,int(sys.argv[1])):
    f.write('info%s(i);\n' %(i))
    f.write('warn%s(i);\n' %(i))
    f.write('error%s(i);\n' %(i))
    f.write('debug%s(i);\n' %(i))
    f.write('fatal%s(i);\n' %(i))

f.write('}\n')
f.write('}\n')

The script takes two arguments. The first argument is the number of calls to make inside the for loop (a value of 1 will actually produce an info, warning, error, debug and fatal call). The second argument is the number times the for loop will iterate. It does the "funkiness" with functions because without it gcc was running out of memory trying to optimize the code when the first argument was high (1000).

So, for example, with arguments "1 1", the script generates:

void info0(int i) { ROS_INFO("Info0: %d", i); }
void warn0(int i) { ROS_WARNING("Warn0: %d", i); }
void error0(int i) { ROS_ERROR("Error0: %d", i); }
void debug0(int i) { ROS_DEBUG("Debug0: %d", i); }
void fatal0(int i) { ROS_FATAL("Fatal0: %d", i); }
int main(int argc, char** argv)
{
for (int i = 0;i < 1; ++i)
{
info0(i);
warn0(i);
error0(i);
debug0(i);
fatal0(i);
}
}

Each test was done ten times, and the average computed. The tests are all with logging turned entirely off, since that is the case where rlog touts its speed.

Test 1: 100 100

log4cxx: 0.004s
rlog: 0.005s

Test 2: 1000 1000

log4cxx: 0.124s
rlog: 0.180s

Test 3: 1 1000000

This is the "tight loop" test... rlog should (and does) dominate here.

log4cxx: 0.066s
rlog: 0.016s

Test 4: 100 1000000

log4cxx: 8.298s
rlog: 5.098s

Test 5: 1000 1

RLog's worst enemy... it does some initialization the first time each logging statement is called.

log4cxx: 0.004s
rlog: 0.107s

Other logging packages

Wiki: rosconsole/Package_proposal (last edited 2016-10-11 14:17:58 by VioletSteenhoff)