rosconsole.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 // Author: Josh Faust
00031 
00032 #if defined(__APPLE__) && defined(__GNUC__) && defined(__llvm__) && !defined(__clang__) && (__GNUC__ == 4) && (__GNUC_MINOR__ == 2)
00033 #error This code is known to provoke a compiler crash with llvm-gcc 4.2. You will have better luck with clang++. See code.ros.org/trac/ros/ticket/3626
00034 #endif
00035 
00036 #include "ros/console.h"
00037 #include "ros/assert.h"
00038 #include <ros/time.h>
00039 
00040 #include <boost/thread.hpp>
00041 #include <boost/shared_array.hpp>
00042 #include <boost/regex.hpp>
00043 
00044 #include <cstdarg>
00045 #include <cstdlib>
00046 #include <cstdio>
00047 #include <memory>
00048 #include <cstring>
00049 #include <stdexcept>
00050 
00051 // declare interface for rosconsole implementations
00052 namespace ros
00053 {
00054 namespace console
00055 {
00056 namespace impl
00057 {
00058 
00059 void initialize();
00060 
00061 void shutdown();
00062 
00063 void register_appender(LogAppender* appender);
00064 
00065 void print(void* handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
00066 
00067 bool isEnabledFor(void* handle, ::ros::console::Level level);
00068 
00069 void* getHandle(const std::string& name);
00070 
00071 std::string getName(void* handle);
00072 
00073 bool get_loggers(std::map<std::string, levels::Level>& loggers);
00074 
00075 bool set_logger_level(const std::string& name, levels::Level level);
00076 
00077 } // namespace impl
00078 
00079 
00080 bool g_initialized = false;
00081 bool g_shutting_down = false;
00082 boost::mutex g_init_mutex;
00083 
00084 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
00085 log4cxx::LevelPtr g_level_lookup[levels::Count] =
00086 {
00087   log4cxx::Level::getDebug(),
00088   log4cxx::Level::getInfo(),
00089   log4cxx::Level::getWarn(),
00090   log4cxx::Level::getError(),
00091   log4cxx::Level::getFatal(),
00092 };
00093 #endif
00094 std::string g_last_error_message = "Unknown Error";
00095 
00096 #ifdef WIN32
00097   #define COLOR_NORMAL ""
00098   #define COLOR_RED ""
00099   #define COLOR_GREEN ""
00100   #define COLOR_YELLOW ""
00101 #else
00102   #define COLOR_NORMAL "\033[0m"
00103   #define COLOR_RED "\033[31m"
00104   #define COLOR_GREEN "\033[32m"
00105   #define COLOR_YELLOW "\033[33m"
00106 #endif
00107 const char* g_format_string = "[${severity}] [${time}]: ${message}";
00108 
00109 typedef std::map<std::string, std::string> M_string;
00110 M_string g_extra_fixed_tokens;
00111 
00112 void setFixedFilterToken(const std::string& key, const std::string& val)
00113 {
00114   g_extra_fixed_tokens[key] = val;
00115 }
00116 
00117 struct FixedToken : public Token
00118 {
00119   FixedToken(const std::string& str)
00120   : str_(str)
00121   {}
00122 
00123   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int)
00124   {
00125     return str_.c_str();
00126   }
00127 
00128   std::string str_;
00129 };
00130 
00131 struct FixedMapToken : public Token
00132 {
00133   FixedMapToken(const std::string& str)
00134   : str_(str)
00135   {}
00136 
00137   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int)
00138   {
00139     M_string::iterator it = g_extra_fixed_tokens.find(str_);
00140     if (it == g_extra_fixed_tokens.end())
00141     {
00142       return ("${" + str_ + "}").c_str();
00143     }
00144 
00145     return it->second.c_str();
00146   }
00147 
00148   std::string str_;
00149 };
00150 
00151 struct PlaceHolderToken : public Token
00152 {
00153   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int)
00154   {
00155     return "PLACEHOLDER";
00156   }
00157 };
00158 
00159 struct SeverityToken : public Token
00160 {
00161   virtual std::string getString(void*, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
00162   {
00163     if (level == levels::Fatal)
00164     {
00165       return "FATAL";
00166     }
00167     else if (level == levels::Error)
00168     {
00169       return "ERROR";
00170     }
00171     else if (level == levels::Warn)
00172     {
00173       return " WARN";
00174     }
00175     else if (level == levels::Info)
00176     {
00177       return " INFO";
00178     }
00179     else if (level == levels::Debug)
00180     {
00181       return "DEBUG";
00182     }
00183 
00184     return "UNKNO";
00185   }
00186 };
00187 
00188 struct MessageToken : public Token
00189 {
00190   virtual std::string getString(void*, ::ros::console::Level, const char* str, const char*, const char*, int)
00191   {
00192     return str;
00193   }
00194 };
00195 
00196 struct TimeToken : public Token
00197 {
00198   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int)
00199   {
00200     std::stringstream ss;
00201     if (ros::Time::isValid() && ros::Time::isSimTime())
00202     {
00203       ss << ros::WallTime::now() << ", " << ros::Time::now();
00204     }
00205     else
00206     {
00207       ss << ros::WallTime::now();
00208     }
00209     return ss.str();
00210   }
00211 };
00212 
00213 struct ThreadToken : public Token
00214 {
00215   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int)
00216   {
00217     std::stringstream ss;
00218     ss << boost::this_thread::get_id();
00219     return ss.str();
00220   }
00221 };
00222 
00223 struct LoggerToken : public Token
00224 {
00225   virtual std::string getString(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
00226   {
00227     return ::ros::console::impl::getName(logger_handle);
00228   }
00229 };
00230 
00231 struct FileToken : public Token
00232 {
00233   virtual std::string getString(void*, ::ros::console::Level, const char*, const char* file, const char*, int)
00234   {
00235     return file;
00236   }
00237 };
00238 
00239 struct FunctionToken : public Token
00240 {
00241   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char* function, int)
00242   {
00243     return function;
00244   }
00245 };
00246 
00247 struct LineToken : public Token
00248 {
00249   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int line)
00250   {
00251     std::stringstream ss;
00252     ss << line;
00253     return ss.str();
00254   }
00255 };
00256 
00257 TokenPtr createTokenFromType(const std::string& type)
00258 {
00259   if (type == "severity")
00260   {
00261     return TokenPtr(new SeverityToken());
00262   }
00263   else if (type == "message")
00264   {
00265     return TokenPtr(new MessageToken());
00266   }
00267   else if (type == "time")
00268   {
00269     return TokenPtr(new TimeToken());
00270   }
00271   else if (type == "thread")
00272   {
00273     return TokenPtr(new ThreadToken());
00274   }
00275   else if (type == "logger")
00276   {
00277     return TokenPtr(new LoggerToken());
00278   }
00279   else if (type == "file")
00280   {
00281     return TokenPtr(new FileToken());
00282   }
00283   else if (type == "line")
00284   {
00285     return TokenPtr(new LineToken());
00286   }
00287   else if (type == "function")
00288   {
00289     return TokenPtr(new FunctionToken());
00290   }
00291 
00292   return TokenPtr(new FixedMapToken(type));
00293 }
00294 
00295 void Formatter::init(const char* fmt)
00296 {
00297   format_ = fmt;
00298 
00299   boost::regex e("\\$\\{([a-z|A-Z]+)\\}");
00300   boost::match_results<std::string::const_iterator> results;
00301   std::string::const_iterator start, end;
00302   start = format_.begin();
00303   end = format_.end();
00304   bool matched_once = false;
00305   std::string last_suffix;
00306   while (boost::regex_search(start, end, results, e))
00307   {
00308 #if 0
00309     for (size_t i = 0; i < results.size(); ++i)
00310     {
00311       std::cout << i << "|" << results.prefix() << "|" <<  results[i] << "|" << results.suffix() << std::endl;
00312     }
00313 #endif
00314 
00315     std::string token = results[1];
00316     last_suffix = results.suffix();
00317     tokens_.push_back(TokenPtr(new FixedToken(results.prefix())));
00318     tokens_.push_back(createTokenFromType(token));
00319 
00320     start = results[0].second;
00321     matched_once = true;
00322   }
00323 
00324   if (matched_once)
00325   {
00326     tokens_.push_back(TokenPtr(new FixedToken(last_suffix)));
00327   }
00328   else
00329   {
00330     tokens_.push_back(TokenPtr(new FixedToken(format_)));
00331   }
00332 }
00333 
00334 void Formatter::print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
00335 {
00336   const char* color = NULL;
00337   FILE* f = stdout;
00338 
00339   if (level == levels::Fatal)
00340   {
00341     color = COLOR_RED;
00342     f = stderr;
00343   }
00344   else if (level == levels::Error)
00345   {
00346     color = COLOR_RED;
00347     f = stderr;
00348   }
00349   else if (level == levels::Warn)
00350   {
00351     color = COLOR_YELLOW;
00352   }
00353   else if (level == levels::Info)
00354   {
00355     color = COLOR_NORMAL;
00356   }
00357   else if (level == levels::Debug)
00358   {
00359     color = COLOR_GREEN;
00360   }
00361 
00362   ROS_ASSERT(color != NULL);
00363 
00364   std::stringstream ss;
00365   ss << color;
00366   V_Token::iterator it = tokens_.begin();
00367   V_Token::iterator end = tokens_.end();
00368   for (; it != end; ++it)
00369   {
00370     ss << (*it)->getString(logger_handle, level, str, file, function, line);
00371   }
00372   ss << COLOR_NORMAL;
00373 
00374   fprintf(f, "%s\n", ss.str().c_str());
00375 }
00376 
00377 Formatter g_formatter;
00378 
00379 
00380 void _print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line)
00381 {
00382   g_formatter.print(logger_handle, level, str, file, function, line);
00383 }
00384 
00385 void initialize()
00386 {
00387   boost::mutex::scoped_lock lock(g_init_mutex);
00388 
00389   if (!g_initialized)
00390   {
00391     // Check for the format string environment variable
00392     char* format_string = NULL;
00393 #ifdef _MSC_VER
00394     _dupenv_s(&format_string, NULL, "ROSCONSOLE_FORMAT");
00395 #else
00396     format_string =  getenv("ROSCONSOLE_FORMAT");
00397 #endif
00398     if (format_string)
00399     {
00400       g_format_string = format_string;
00401     }
00402 
00403     g_formatter.init(g_format_string);
00404     backend::function_notifyLoggerLevelsChanged = notifyLoggerLevelsChanged;
00405     backend::function_print = _print;
00406 
00407     ::ros::console::impl::initialize();
00408     g_initialized = true;
00409   }
00410 }
00411 
00412 void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args)
00413 {
00414 #ifdef _MSC_VER
00415   va_list arg_copy = args; // dangerous?
00416 #else
00417   va_list arg_copy;
00418   va_copy(arg_copy, args);
00419 #endif
00420 #ifdef _MSC_VER
00421   size_t total = vsnprintf_s(buffer.get(), buffer_size, buffer_size, fmt, args);
00422 #else
00423   size_t total = vsnprintf(buffer.get(), buffer_size, fmt, args);
00424 #endif
00425   if (total >= buffer_size)
00426   {
00427     buffer_size = total + 1;
00428     buffer.reset(new char[buffer_size]);
00429 
00430 #ifdef _MSC_VER
00431     vsnprintf_s(buffer.get(), buffer_size, buffer_size, fmt, arg_copy);
00432 #else
00433     vsnprintf(buffer.get(), buffer_size, fmt, arg_copy);
00434 #endif
00435   }
00436   va_end(arg_copy);
00437 }
00438 
00439 void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...)
00440 {
00441   va_list args;
00442   va_start(args, fmt);
00443 
00444   vformatToBuffer(buffer, buffer_size, fmt, args);
00445 
00446   va_end(args);
00447 }
00448 
00449 std::string formatToString(const char* fmt, ...)
00450 {
00451   boost::shared_array<char> buffer;
00452   size_t size = 0;
00453 
00454   va_list args;
00455   va_start(args, fmt);
00456 
00457   vformatToBuffer(buffer, size, fmt, args);
00458 
00459   va_end(args);
00460 
00461   return std::string(buffer.get(), size);
00462 }
00463 
00464 #define INITIAL_BUFFER_SIZE 4096
00465 static boost::mutex g_print_mutex;
00466 static boost::shared_array<char> g_print_buffer(new char[INITIAL_BUFFER_SIZE]);
00467 static size_t g_print_buffer_size = INITIAL_BUFFER_SIZE;
00468 static boost::thread::id g_printing_thread_id;
00469 void print(FilterBase* filter, void* logger_handle, Level level, 
00470            const char* file, int line, const char* function, const char* fmt, ...)
00471 {
00472   if (g_shutting_down)
00473     return;
00474 
00475   if (g_printing_thread_id == boost::this_thread::get_id())
00476   {
00477     fprintf(stderr, "Warning: recursive print statement has occurred.  Throwing out recursive print.\n");
00478     return;
00479   }
00480 
00481   boost::mutex::scoped_lock lock(g_print_mutex);
00482 
00483   g_printing_thread_id = boost::this_thread::get_id();
00484 
00485   va_list args;
00486   va_start(args, fmt);
00487 
00488   vformatToBuffer(g_print_buffer, g_print_buffer_size, fmt, args);
00489 
00490   va_end(args);
00491 
00492   bool enabled = true;
00493 
00494   if (filter)
00495   {
00496     FilterParams params;
00497     params.file = file;
00498     params.function = function;
00499     params.line = line;
00500     params.level = level;
00501     params.logger = logger_handle;
00502     params.message = g_print_buffer.get();
00503     enabled = filter->isEnabled(params);
00504     level = params.level;
00505 
00506     if (!params.out_message.empty())
00507     {
00508       size_t msg_size = params.out_message.size();
00509       if (g_print_buffer_size <= msg_size)
00510       {
00511         g_print_buffer_size = msg_size + 1;
00512         g_print_buffer.reset(new char[g_print_buffer_size]);
00513       }
00514 
00515       memcpy(g_print_buffer.get(), params.out_message.c_str(), msg_size + 1);
00516     }
00517   }
00518 
00519   if (enabled)
00520   {
00521     if (level == levels::Error)
00522     {
00523       g_last_error_message = g_print_buffer.get();
00524     }
00525     try
00526     {
00527       ::ros::console::impl::print(logger_handle, level, g_print_buffer.get(), file, function, line);
00528     }
00529     catch (std::exception& e)
00530     {
00531       fprintf(stderr, "Caught exception while logging: [%s]\n", e.what());
00532     }
00533   }
00534 
00535   g_printing_thread_id = boost::thread::id();
00536 }
00537 
00538 void print(FilterBase* filter, void* logger_handle, Level level, 
00539            const std::stringstream& ss, const char* file, int line, const char* function)
00540 {
00541   if (g_shutting_down)
00542     return;
00543 
00544   if (g_printing_thread_id == boost::this_thread::get_id())
00545   {
00546     fprintf(stderr, "Warning: recursive print statement has occurred.  Throwing out recursive print.\n");
00547     return;
00548   }
00549 
00550   boost::mutex::scoped_lock lock(g_print_mutex);
00551 
00552   g_printing_thread_id = boost::this_thread::get_id();
00553 
00554   bool enabled = true;
00555   std::string str = ss.str();
00556 
00557   if (filter)
00558   {
00559     FilterParams params;
00560     params.file = file;
00561     params.function = function;
00562     params.line = line;
00563     params.level = level;
00564     params.logger = logger_handle;
00565     params.message = g_print_buffer.get();
00566     enabled = filter->isEnabled(params);
00567     level = params.level;
00568 
00569     if (!params.out_message.empty())
00570     {
00571       str = params.out_message;
00572     }
00573   }
00574 
00575   if (enabled)
00576   {
00577     if (level == levels::Error)
00578     {
00579       g_last_error_message = str;
00580     }
00581     try
00582     {
00583       ::ros::console::impl::print(logger_handle, level, str.c_str(), file, function, line);
00584     }
00585     catch (std::exception& e)
00586     {
00587       fprintf(stderr, "Caught exception while logging: [%s]\n", e.what());
00588     }
00589   }
00590 
00591   g_printing_thread_id = boost::thread::id();
00592 }
00593 
00594 typedef std::vector<LogLocation*> V_LogLocation;
00595 V_LogLocation g_log_locations;
00596 boost::mutex g_locations_mutex;
00597 void registerLogLocation(LogLocation* loc)
00598 {
00599   boost::mutex::scoped_lock lock(g_locations_mutex);
00600 
00601   g_log_locations.push_back(loc);
00602 }
00603 
00604 void checkLogLocationEnabledNoLock(LogLocation* loc)
00605 {
00606   loc->logger_enabled_ = ::ros::console::impl::isEnabledFor(loc->logger_, loc->level_);
00607 }
00608 
00609 void initializeLogLocation(LogLocation* loc, const std::string& name, Level level)
00610 {
00611   boost::mutex::scoped_lock lock(g_locations_mutex);
00612 
00613   if (loc->initialized_)
00614   {
00615     return;
00616   }
00617 
00618   loc->logger_ = ::ros::console::impl::getHandle(name);
00619   loc->level_ = level;
00620 
00621   g_log_locations.push_back(loc);
00622 
00623   checkLogLocationEnabledNoLock(loc);
00624 
00625   loc->initialized_ = true;
00626 }
00627 
00628 void setLogLocationLevel(LogLocation* loc, Level level)
00629 {
00630   boost::mutex::scoped_lock lock(g_locations_mutex);
00631   loc->level_ = level;
00632 }
00633 
00634 void checkLogLocationEnabled(LogLocation* loc)
00635 {
00636   boost::mutex::scoped_lock lock(g_locations_mutex);
00637   checkLogLocationEnabledNoLock(loc);
00638 }
00639 
00640 void notifyLoggerLevelsChanged()
00641 {
00642   boost::mutex::scoped_lock lock(g_locations_mutex);
00643 
00644   V_LogLocation::iterator it = g_log_locations.begin();
00645   V_LogLocation::iterator end = g_log_locations.end();
00646   for ( ; it != end; ++it )
00647   {
00648     LogLocation* loc = *it;
00649     checkLogLocationEnabledNoLock(loc);
00650   }
00651 }
00652 
00653 class StaticInit
00654 {
00655 public:
00656   StaticInit()
00657   {
00658     ROSCONSOLE_AUTOINIT;
00659   }
00660 };
00661 StaticInit g_static_init;
00662 
00663 
00664 void register_appender(LogAppender* appender)
00665 {
00666   ros::console::impl::register_appender(appender);
00667 }
00668 
00669 void shutdown() 
00670 {
00671   g_shutting_down = true;
00672   ros::console::impl::shutdown();
00673 }
00674 
00675 bool get_loggers(std::map<std::string, levels::Level>& loggers)
00676 {
00677   return ros::console::impl::get_loggers(loggers);
00678 }
00679 
00680 bool set_logger_level(const std::string& name, levels::Level level)
00681 {
00682   return ros::console::impl::set_logger_level(name, level);
00683 }
00684 
00685 } // namespace console
00686 } // namespace ros


rosconsole
Author(s): Josh Faust
autogenerated on Fri Aug 28 2015 12:33:01