console.h
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 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 #ifndef ROSCONSOLE_ROSCONSOLE_H
00033 #define ROSCONSOLE_ROSCONSOLE_H
00034 
00035 #include "console_backend.h"
00036 
00037 #include <cstdio>
00038 #include <sstream>
00039 #include <ros/time.h>
00040 #include <cstdarg>
00041 #include <ros/macros.h>
00042 #include <map>
00043 #include <vector>
00044 
00045 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
00046 #include "log4cxx/level.h"
00047 #endif
00048 
00049 // Import/export for windows dll's and visibility for gcc shared libraries.
00050 
00051 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
00052   #ifdef rosconsole_EXPORTS // we are building a shared lib/dll
00053     #define ROSCONSOLE_DECL ROS_HELPER_EXPORT
00054   #else // we are using shared lib/dll
00055     #define ROSCONSOLE_DECL ROS_HELPER_IMPORT
00056   #endif
00057 #else // ros is being built around static libraries
00058   #define ROSCONSOLE_DECL
00059 #endif
00060 
00061 #ifdef __GNUC__
00062 #if __GNUC__ >= 3
00063 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b) __attribute__ ((__format__ (__printf__, a, b)));
00064 #endif
00065 #endif
00066 
00067 #ifndef ROSCONSOLE_PRINTF_ATTRIBUTE
00068 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
00069 #endif
00070 
00071 namespace boost
00072 {
00073 template<typename T> class shared_array;
00074 }
00075 
00076 namespace ros
00077 {
00078 namespace console
00079 {
00080 
00081 ROSCONSOLE_DECL void shutdown();
00082 
00083 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
00084 extern ROSCONSOLE_DECL log4cxx::LevelPtr g_level_lookup[];
00085 #endif
00086 
00087 extern ROSCONSOLE_DECL bool get_loggers(std::map<std::string, levels::Level>& loggers);
00088 extern ROSCONSOLE_DECL bool set_logger_level(const std::string& name, levels::Level level);
00089 
00093 extern ROSCONSOLE_DECL bool g_initialized;
00094 
00098 extern ROSCONSOLE_DECL std::string g_last_error_message;
00099 
00100 class LogAppender
00101 {
00102 public:
00103 
00104   virtual void log(::ros::console::Level level, const char* str, const char* file, const char* function, int line) = 0;
00105 
00106 };
00107 
00108 ROSCONSOLE_DECL void register_appender(LogAppender* appender);
00109 
00110 struct Token
00111 {
00112   /*
00113    * @param level
00114    * @param message
00115    * @param file
00116    * @param function
00117    * @param  line
00118    */
00119   virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int) = 0;
00120 };
00121 typedef boost::shared_ptr<Token> TokenPtr;
00122 typedef std::vector<TokenPtr> V_Token;
00123 
00124 struct Formatter
00125 {
00126   void init(const char* fmt);
00127   void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
00128   std::string format_;
00129   V_Token tokens_;
00130 };
00131 
00135 extern ROSCONSOLE_DECL Formatter g_formatter;
00136 
00143 ROSCONSOLE_DECL void initialize();
00144 
00145 class FilterBase;
00153 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
00154            const char* file, int line, 
00155            const char* function, const char* fmt, ...) ROSCONSOLE_PRINTF_ATTRIBUTE(7, 8);
00156 
00157 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
00158            const std::stringstream& str, const char* file, int line, const char* function);
00159 
00160 struct ROSCONSOLE_DECL LogLocation;
00161 
00169 ROSCONSOLE_DECL void registerLogLocation(LogLocation* loc);
00170 
00179 ROSCONSOLE_DECL void notifyLoggerLevelsChanged();
00180 
00181 ROSCONSOLE_DECL void setFixedFilterToken(const std::string& key, const std::string& val);
00182 
00186 struct FilterParams
00187 {
00188   // input parameters
00189   const char* file;                         
00190   int line;                                 
00191   const char* function;                     
00192   const char* message;                      
00193 
00194   // input/output parameters
00195   void* logger;                             
00196   Level level;                              
00197 
00198   // output parameters
00199   std::string out_message;                  
00200 };
00201 
00223 class FilterBase
00224 {
00225 public:
00226   virtual ~FilterBase() {}
00231   inline virtual bool isEnabled() { return true; }
00236   inline virtual bool isEnabled(FilterParams&) { return true; }
00237 };
00238 
00239 struct ROSCONSOLE_DECL LogLocation;
00243 ROSCONSOLE_DECL void initializeLogLocation(LogLocation* loc, const std::string& name, Level level);
00247 ROSCONSOLE_DECL void setLogLocationLevel(LogLocation* loc, Level level);
00251 ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation* loc);
00252 
00256 struct LogLocation
00257 {
00258   bool initialized_;
00259   bool logger_enabled_;
00260   ::ros::console::Level level_;
00261   void* logger_;
00262 };
00263 
00264 ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args);
00265 ROSCONSOLE_DECL void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...);
00266 ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);
00267 
00268 } // namespace console
00269 } // namespace ros
00270 
00271 #ifdef WIN32
00272 #define ROS_LIKELY(x)       (x)
00273 #define ROS_UNLIKELY(x)     (x)
00274 #else
00275 #define ROS_LIKELY(x)       __builtin_expect((x),1)
00276 #define ROS_UNLIKELY(x)     __builtin_expect((x),0)
00277 #endif
00278 
00279 #if defined(MSVC)
00280   #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
00281 #elif defined(__GNUC__)
00282   #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
00283 #else
00284   #define __ROSCONSOLE_FUNCTION__ ""
00285 #endif
00286 
00287 
00288 #ifdef ROS_PACKAGE_NAME
00289 #define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
00290 #else
00291 #define ROSCONSOLE_PACKAGE_NAME "unknown_package"
00292 #endif
00293 
00294 #define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
00295 #define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
00296 #define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX
00297 
00298 // These allow you to compile-out everything below a certain severity level if necessary
00299 #define ROSCONSOLE_SEVERITY_DEBUG 0
00300 #define ROSCONSOLE_SEVERITY_INFO 1
00301 #define ROSCONSOLE_SEVERITY_WARN 2
00302 #define ROSCONSOLE_SEVERITY_ERROR 3
00303 #define ROSCONSOLE_SEVERITY_FATAL 4
00304 #define ROSCONSOLE_SEVERITY_NONE 5
00305 
00311 #ifndef ROSCONSOLE_MIN_SEVERITY
00312 #define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
00313 #endif
00314 
00319 #define ROSCONSOLE_AUTOINIT \
00320   do \
00321   { \
00322     if (ROS_UNLIKELY(!::ros::console::g_initialized)) \
00323     { \
00324       ::ros::console::initialize(); \
00325     } \
00326   } while(0)
00327 
00328 #define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
00329   ROSCONSOLE_AUTOINIT; \
00330   static ::ros::console::LogLocation __rosconsole_define_location__loc = {false, false, ::ros::console::levels::Count, 0}; /* Initialized at compile-time */ \
00331   if (ROS_UNLIKELY(!__rosconsole_define_location__loc.initialized_)) \
00332   { \
00333     initializeLogLocation(&__rosconsole_define_location__loc, name, level); \
00334   } \
00335   if (ROS_UNLIKELY(__rosconsole_define_location__loc.level_ != level)) \
00336   { \
00337     setLogLocationLevel(&__rosconsole_define_location__loc, level); \
00338     checkLogLocationEnabled(&__rosconsole_define_location__loc); \
00339   } \
00340   bool __rosconsole_define_location__enabled = __rosconsole_define_location__loc.logger_enabled_ && (cond);
00341 
00342 #define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
00343     ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)
00344 
00345 #define ROSCONSOLE_PRINT_AT_LOCATION(...) \
00346     ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(0, __VA_ARGS__)
00347 
00348 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
00349 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
00350   do \
00351   { \
00352     std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
00353     __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
00354     ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __rosconsole_print_stream_at_location_with_filter__ss__, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__); \
00355   } while (0)
00356 
00357 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
00358     ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(0, args)
00359 
00369 #define ROS_LOG_COND(cond, level, name, ...) \
00370   do \
00371   { \
00372     ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
00373     \
00374     if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
00375     { \
00376       ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00377     } \
00378   } while(0)
00379 
00389 #define ROS_LOG_STREAM_COND(cond, level, name, args) \
00390   do \
00391   { \
00392     ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
00393     if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
00394     { \
00395       ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00396     } \
00397   } while(0)
00398 
00405 #define ROS_LOG_ONCE(level, name, ...) \
00406   do \
00407   { \
00408     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00409     static bool hit = false; \
00410     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
00411     { \
00412       hit = true; \
00413       ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00414     } \
00415   } while(0)
00416 
00417 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
00424 #define ROS_LOG_STREAM_ONCE(level, name, args) \
00425   do \
00426   { \
00427     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00428     static bool __ros_log_stream_once__hit__ = false; \
00429     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
00430     { \
00431       __ros_log_stream_once__hit__ = true; \
00432       ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00433     } \
00434   } while(0)
00435 
00443 #define ROS_LOG_THROTTLE(rate, level, name, ...) \
00444   do \
00445   { \
00446     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00447     static double last_hit = 0.0; \
00448     ::ros::Time now = ::ros::Time::now(); \
00449     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(last_hit + rate <= now.toSec())) \
00450     { \
00451       last_hit = now.toSec(); \
00452       ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00453     } \
00454   } while(0)
00455 
00456 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
00464 #define ROS_LOG_STREAM_THROTTLE(rate, level, name, args) \
00465   do \
00466   { \
00467     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00468     static double __ros_log_stream_throttle__last_hit__ = 0.0; \
00469     ::ros::Time __ros_log_stream_throttle__now__ = ::ros::Time::now(); \
00470     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_throttle__last_hit__ + rate <= __ros_log_stream_throttle__now__.toSec())) \
00471     { \
00472       __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__.toSec(); \
00473       ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00474     } \
00475   } while(0)
00476 
00484 #define ROS_LOG_DELAYED_THROTTLE(rate, level, name, ...) \
00485   do \
00486   { \
00487     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00488     ::ros::Time __ros_log_delayed_throttle__now__ = ::ros::Time::now(); \
00489     static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
00490     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_delayed_throttle__last_hit__ + rate <= __ros_log_delayed_throttle__now__.toSec())) \
00491     { \
00492       __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
00493       ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00494     } \
00495   } while(0)
00496 
00497 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
00505 #define ROS_LOG_STREAM_DELAYED_THROTTLE(rate, level, name, args) \
00506   do \
00507   { \
00508     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00509     ::ros::Time __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now(); \
00510     static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
00511     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_delayed_throttle__last_hit__ + rate <= __ros_log_stream_delayed_throttle__now__.toSec())) \
00512     { \
00513       __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
00514       ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00515     } \
00516   } while(0)
00517 
00525 #define ROS_LOG_FILTER(filter, level, name, ...) \
00526   do \
00527   { \
00528     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00529     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
00530     { \
00531       ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
00532     } \
00533   } while(0)
00534 
00542 #define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
00543   do \
00544   { \
00545     ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00546     if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
00547     { \
00548       ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
00549     } \
00550   } while(0)
00551 
00558 #define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
00559 
00565 #define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)
00566 
00567 #include "rosconsole/macros_generated.h"
00568 
00569 #endif // ROSCONSOLE_ROSCONSOLE_H


rosconsole
Author(s): Josh Faust
autogenerated on Tue Mar 7 2017 03:44:27