00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
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
00044 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
00045 #include "log4cxx/level.h"
00046 #endif
00047
00048
00049
00050 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
00051 #ifdef rosconsole_EXPORTS // we are building a shared lib/dll
00052 #define ROSCONSOLE_DECL ROS_HELPER_EXPORT
00053 #else // we are using shared lib/dll
00054 #define ROSCONSOLE_DECL ROS_HELPER_IMPORT
00055 #endif
00056 #else // ros is being built around static libraries
00057 #define ROSCONSOLE_DECL
00058 #endif
00059
00060 #ifdef __GNUC__
00061 #if __GNUC__ >= 3
00062 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b) __attribute__ ((__format__ (__printf__, a, b)));
00063 #endif
00064 #endif
00065
00066 #ifndef ROSCONSOLE_PRINTF_ATTRIBUTE
00067 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
00068 #endif
00069
00070 namespace boost
00071 {
00072 template<typename T> class shared_array;
00073 }
00074
00075 namespace ros
00076 {
00077 namespace console
00078 {
00079
00080 ROSCONSOLE_DECL void shutdown();
00081
00082 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
00083 extern ROSCONSOLE_DECL log4cxx::LevelPtr g_level_lookup[];
00084 #endif
00085
00086 extern ROSCONSOLE_DECL bool get_loggers(std::map<std::string, levels::Level>& loggers);
00087 extern ROSCONSOLE_DECL bool set_logger_level(const std::string& name, levels::Level level);
00088
00092 extern ROSCONSOLE_DECL bool g_initialized;
00093
00097 extern ROSCONSOLE_DECL std::string g_last_error_message;
00098
00099 class LogAppender
00100 {
00101 public:
00102
00103 virtual void log(::ros::console::Level level, const char* str, const char* file, const char* function, int line) = 0;
00104
00105 };
00106
00107 ROSCONSOLE_DECL void register_appender(LogAppender* appender);
00108
00109 struct Token
00110 {
00111
00112
00113
00114
00115
00116
00117
00118 virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int) = 0;
00119 };
00120 typedef boost::shared_ptr<Token> TokenPtr;
00121 typedef std::vector<TokenPtr> V_Token;
00122
00123 struct Formatter
00124 {
00125 void init(const char* fmt);
00126 void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
00127 std::string format_;
00128 V_Token tokens_;
00129 };
00130
00134 extern ROSCONSOLE_DECL Formatter g_formatter;
00135
00142 ROSCONSOLE_DECL void initialize();
00143
00144 class FilterBase;
00152 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
00153 const char* file, int line,
00154 const char* function, const char* fmt, ...) ROSCONSOLE_PRINTF_ATTRIBUTE(7, 8);
00155
00156 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
00157 const std::stringstream& str, const char* file, int line, const char* function);
00158
00159 struct ROSCONSOLE_DECL LogLocation;
00160
00168 ROSCONSOLE_DECL void registerLogLocation(LogLocation* loc);
00169
00178 ROSCONSOLE_DECL void notifyLoggerLevelsChanged();
00179
00180 ROSCONSOLE_DECL void setFixedFilterToken(const std::string& key, const std::string& val);
00181
00185 struct FilterParams
00186 {
00187
00188 const char* file;
00189 int line;
00190 const char* function;
00191 const char* message;
00192
00193
00194 void* logger;
00195 Level level;
00196
00197
00198 std::string out_message;
00199 };
00200
00222 class FilterBase
00223 {
00224 public:
00225 virtual ~FilterBase() {}
00230 inline virtual bool isEnabled() { return true; }
00235 inline virtual bool isEnabled(FilterParams&) { return true; }
00236 };
00237
00238 struct ROSCONSOLE_DECL LogLocation;
00242 ROSCONSOLE_DECL void initializeLogLocation(LogLocation* loc, const std::string& name, Level level);
00246 ROSCONSOLE_DECL void setLogLocationLevel(LogLocation* loc, Level level);
00250 ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation* loc);
00251
00255 struct LogLocation
00256 {
00257 bool initialized_;
00258 bool logger_enabled_;
00259 ::ros::console::Level level_;
00260 void* logger_;
00261 };
00262
00263 ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args);
00264 ROSCONSOLE_DECL void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...);
00265 ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);
00266
00267 }
00268 }
00269
00270 #ifdef WIN32
00271 #define ROS_LIKELY(x) (x)
00272 #define ROS_UNLIKELY(x) (x)
00273 #else
00274 #define ROS_LIKELY(x) __builtin_expect((x),1)
00275 #define ROS_UNLIKELY(x) __builtin_expect((x),0)
00276 #endif
00277
00278 #if defined(MSVC)
00279 #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
00280 #elif defined(__GNUC__)
00281 #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
00282 #else
00283 #define __ROSCONSOLE_FUNCTION__ ""
00284 #endif
00285
00286
00287 #ifdef ROS_PACKAGE_NAME
00288 #define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
00289 #else
00290 #define ROSCONSOLE_PACKAGE_NAME "unknown_package"
00291 #endif
00292
00293 #define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
00294 #define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
00295 #define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX
00296
00297
00298 #define ROSCONSOLE_SEVERITY_DEBUG 0
00299 #define ROSCONSOLE_SEVERITY_INFO 1
00300 #define ROSCONSOLE_SEVERITY_WARN 2
00301 #define ROSCONSOLE_SEVERITY_ERROR 3
00302 #define ROSCONSOLE_SEVERITY_FATAL 4
00303 #define ROSCONSOLE_SEVERITY_NONE 5
00304
00310 #ifndef ROSCONSOLE_MIN_SEVERITY
00311 #define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
00312 #endif
00313
00318 #define ROSCONSOLE_AUTOINIT \
00319 do \
00320 { \
00321 if (ROS_UNLIKELY(!::ros::console::g_initialized)) \
00322 { \
00323 ::ros::console::initialize(); \
00324 } \
00325 } while(0)
00326
00327 #define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
00328 ROSCONSOLE_AUTOINIT; \
00329 static ::ros::console::LogLocation loc = {false, false, ::ros::console::levels::Count, 0}; \
00330 if (ROS_UNLIKELY(!loc.initialized_)) \
00331 { \
00332 initializeLogLocation(&loc, name, level); \
00333 } \
00334 if (ROS_UNLIKELY(loc.level_ != level)) \
00335 { \
00336 setLogLocationLevel(&loc, level); \
00337 checkLogLocationEnabled(&loc); \
00338 } \
00339 bool enabled = loc.logger_enabled_ && (cond);
00340
00341 #define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
00342 ::ros::console::print(filter, loc.logger_, loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)
00343
00344 #define ROSCONSOLE_PRINT_AT_LOCATION(...) \
00345 ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(0, __VA_ARGS__)
00346
00347
00348 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
00349 do \
00350 { \
00351 std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
00352 __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
00353 ::ros::console::print(filter, loc.logger_, loc.level_, __rosconsole_print_stream_at_location_with_filter__ss__, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__); \
00354 } while (0)
00355
00356 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
00357 ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(0, args)
00358
00368 #define ROS_LOG_COND(cond, level, name, ...) \
00369 do \
00370 { \
00371 ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
00372 \
00373 if (ROS_UNLIKELY(enabled)) \
00374 { \
00375 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00376 } \
00377 } while(0)
00378
00388 #define ROS_LOG_STREAM_COND(cond, level, name, args) \
00389 do \
00390 { \
00391 ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
00392 if (ROS_UNLIKELY(enabled)) \
00393 { \
00394 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00395 } \
00396 } while(0)
00397
00404 #define ROS_LOG_ONCE(level, name, ...) \
00405 do \
00406 { \
00407 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00408 static bool hit = false; \
00409 if (ROS_UNLIKELY(enabled) && ROS_UNLIKELY(!hit)) \
00410 { \
00411 hit = true; \
00412 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00413 } \
00414 } while(0)
00415
00416
00423 #define ROS_LOG_STREAM_ONCE(level, name, args) \
00424 do \
00425 { \
00426 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00427 static bool __ros_log_stream_once__hit__ = false; \
00428 if (ROS_UNLIKELY(enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
00429 { \
00430 __ros_log_stream_once__hit__ = true; \
00431 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00432 } \
00433 } while(0)
00434
00442 #define ROS_LOG_THROTTLE(rate, level, name, ...) \
00443 do \
00444 { \
00445 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00446 static double last_hit = 0.0; \
00447 ::ros::Time now = ::ros::Time::now(); \
00448 if (ROS_UNLIKELY(enabled) && ROS_UNLIKELY(last_hit + rate <= now.toSec())) \
00449 { \
00450 last_hit = now.toSec(); \
00451 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
00452 } \
00453 } while(0)
00454
00455
00463 #define ROS_LOG_STREAM_THROTTLE(rate, level, name, args) \
00464 do \
00465 { \
00466 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00467 static double __ros_log_stream_throttle__last_hit__ = 0.0; \
00468 ::ros::Time __ros_log_stream_throttle__now__ = ::ros::Time::now(); \
00469 if (ROS_UNLIKELY(enabled) && ROS_UNLIKELY(__ros_log_stream_throttle__last_hit__ + rate <= __ros_log_stream_throttle__now__.toSec())) \
00470 { \
00471 __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__.toSec(); \
00472 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
00473 } \
00474 } while(0)
00475
00483 #define ROS_LOG_FILTER(filter, level, name, ...) \
00484 do \
00485 { \
00486 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00487 if (ROS_UNLIKELY(enabled) && (filter)->isEnabled()) \
00488 { \
00489 ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
00490 } \
00491 } while(0)
00492
00500 #define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
00501 do \
00502 { \
00503 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
00504 if (ROS_UNLIKELY(enabled) && (filter)->isEnabled()) \
00505 { \
00506 ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
00507 } \
00508 } while(0)
00509
00516 #define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
00517
00523 #define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)
00524
00525 #include "rosconsole/macros_generated.h"
00526
00527 #endif // ROSCONSOLE_ROSCONSOLE_H