console.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 // Author: Josh Faust
31 
32 #ifndef ROSCONSOLE_ROSCONSOLE_H
33 #define ROSCONSOLE_ROSCONSOLE_H
34 
35 #include "console_backend.h"
36 
37 #include <cstdio>
38 #include <sstream>
39 #include <ros/time.h>
40 #include <cstdarg>
41 #include <ros/macros.h>
42 #include <map>
43 #include <vector>
44 
45 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
46 #include "log4cxx/level.h"
47 #endif
48 
49 // Import/export for windows dll's and visibility for gcc shared libraries.
50 
51 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
52  #ifdef rosconsole_EXPORTS // we are building a shared lib/dll
53  #define ROSCONSOLE_DECL ROS_HELPER_EXPORT
54  #else // we are using shared lib/dll
55  #define ROSCONSOLE_DECL ROS_HELPER_IMPORT
56  #endif
57 #else // ros is being built around static libraries
58  #define ROSCONSOLE_DECL
59 #endif
60 
61 #ifdef __GNUC__
62 #if __GNUC__ >= 3
63 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b) __attribute__ ((__format__ (__printf__, a, b)))
64 #endif
65 #endif
66 
67 #ifndef ROSCONSOLE_PRINTF_ATTRIBUTE
68 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
69 #endif
70 
71 namespace boost
72 {
73 template<typename T> class shared_array;
74 }
75 
76 namespace ros
77 {
78 namespace console
79 {
80 
82 
83 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
84 extern ROSCONSOLE_DECL log4cxx::LevelPtr g_level_lookup[];
85 #endif
86 
87 extern ROSCONSOLE_DECL bool get_loggers(std::map<std::string, levels::Level>& loggers);
88 extern ROSCONSOLE_DECL bool set_logger_level(const std::string& name, levels::Level level);
89 
93 extern ROSCONSOLE_DECL bool g_initialized;
94 
98 extern ROSCONSOLE_DECL std::string g_last_error_message;
99 
101 {
102 public:
103 
104  virtual ~LogAppender() {}
105 
106  virtual void log(::ros::console::Level level, const char* str, const char* file, const char* function, int line) = 0;
107 
108 };
109 
111 
113 
114 struct Token
115 {
116  virtual ~Token() {}
117  /*
118  * @param level
119  * @param message
120  * @param file
121  * @param function
122  * @param line
123  */
124  virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int) = 0;
125 };
127 typedef std::vector<TokenPtr> V_Token;
128 
129 struct Formatter
130 {
131  void init(const char* fmt);
132  void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
133  std::string format_;
134  V_Token tokens_;
135 };
136 
141 
149 
150 class FilterBase;
158 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
159  const char* file, int line,
160  const char* function, const char* fmt, ...) ROSCONSOLE_PRINTF_ATTRIBUTE(7, 8);
161 
162 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
163  const std::stringstream& str, const char* file, int line, const char* function);
164 
166 
174 ROSCONSOLE_DECL void registerLogLocation(LogLocation* loc);
175 
185 
186 ROSCONSOLE_DECL void setFixedFilterToken(const std::string& key, const std::string& val);
187 
192 {
193  // input parameters
194  const char* file;
195  int line;
196  const char* function;
197  const char* message;
198 
199  // input/output parameters
200  void* logger;
202 
203  // output parameters
204  std::string out_message;
205 };
206 
229 {
230 public:
231  virtual ~FilterBase() {}
236  inline virtual bool isEnabled() { return true; }
241  inline virtual bool isEnabled(FilterParams&) { return true; }
242 };
243 
244 struct ROSCONSOLE_DECL LogLocation;
248 ROSCONSOLE_DECL void initializeLogLocation(LogLocation* loc, const std::string& name, Level level);
252 ROSCONSOLE_DECL void setLogLocationLevel(LogLocation* loc, Level level);
256 ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation* loc);
257 
261 struct LogLocation
262 {
266  void* logger_;
267 };
268 
269 ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args);
270 ROSCONSOLE_DECL void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...);
271 ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);
272 
273 } // namespace console
274 } // namespace ros
275 
276 #if defined(_MSC_VER)
277 #define ROS_LIKELY(x) (x)
278 #define ROS_UNLIKELY(x) (x)
279 #else
280 #define ROS_LIKELY(x) __builtin_expect((x),1)
281 #define ROS_UNLIKELY(x) __builtin_expect((x),0)
282 #endif
283 
284 #if defined(_MSC_VER)
285  #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
286 #elif defined(__GNUC__)
287  #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
288 #else
289  #define __ROSCONSOLE_FUNCTION__ ""
290 #endif
291 
292 
293 #ifdef ROS_PACKAGE_NAME
294 #define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
295 #else
296 #define ROSCONSOLE_PACKAGE_NAME "unknown_package"
297 #endif
298 
299 #define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
300 #define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
301 #define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX
302 
303 // These allow you to compile-out everything below a certain severity level if necessary
304 #define ROSCONSOLE_SEVERITY_DEBUG 0
305 #define ROSCONSOLE_SEVERITY_INFO 1
306 #define ROSCONSOLE_SEVERITY_WARN 2
307 #define ROSCONSOLE_SEVERITY_ERROR 3
308 #define ROSCONSOLE_SEVERITY_FATAL 4
309 #define ROSCONSOLE_SEVERITY_NONE 5
310 
316 #ifndef ROSCONSOLE_MIN_SEVERITY
317 #define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
318 #endif
319 
324 #define ROSCONSOLE_AUTOINIT \
325  do \
326  { \
327  if (ROS_UNLIKELY(!::ros::console::g_initialized)) \
328  { \
329  ::ros::console::initialize(); \
330  } \
331  } while(false)
332 
333 #define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
334  ROSCONSOLE_AUTOINIT; \
335  static ::ros::console::LogLocation __rosconsole_define_location__loc = {false, false, ::ros::console::levels::Count, NULL}; /* Initialized at compile-time */ \
336  if (ROS_UNLIKELY(!__rosconsole_define_location__loc.initialized_)) \
337  { \
338  initializeLogLocation(&__rosconsole_define_location__loc, name, level); \
339  } \
340  if (ROS_UNLIKELY(__rosconsole_define_location__loc.level_ != level)) \
341  { \
342  setLogLocationLevel(&__rosconsole_define_location__loc, level); \
343  checkLogLocationEnabled(&__rosconsole_define_location__loc); \
344  } \
345  bool __rosconsole_define_location__enabled = __rosconsole_define_location__loc.logger_enabled_ && (cond);
346 
347 #define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
348  ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)
349 
350 #define ROSCONSOLE_PRINT_AT_LOCATION(...) \
351  ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(NULL, __VA_ARGS__)
352 
353 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
354 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
355  do \
356  { \
357  std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
358  __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
359  ::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__); \
360  } while (0)
361 
362 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
363  ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(NULL, args)
364 
369 #define ROSCONSOLE_THROTTLE_CHECK(now, last, period) (ROS_UNLIKELY(last + period <= now) || ROS_UNLIKELY(now < last))
370 
380 #define ROS_LOG_COND(cond, level, name, ...) \
381  do \
382  { \
383  ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
384  \
385  if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
386  { \
387  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
388  } \
389  } while(false)
390 
400 #define ROS_LOG_STREAM_COND(cond, level, name, args) \
401  do \
402  { \
403  ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
404  if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
405  { \
406  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
407  } \
408  } while(false)
409 
416 #define ROS_LOG_ONCE(level, name, ...) \
417  do \
418  { \
419  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
420  static bool hit = false; \
421  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
422  { \
423  hit = true; \
424  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
425  } \
426  } while(false)
427 
428 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
435 #define ROS_LOG_STREAM_ONCE(level, name, args) \
436  do \
437  { \
438  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
439  static bool __ros_log_stream_once__hit__ = false; \
440  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
441  { \
442  __ros_log_stream_once__hit__ = true; \
443  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
444  } \
445  } while(false)
446 
454 #define ROS_LOG_THROTTLE(period, level, name, ...) \
455  do \
456  { \
457  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
458  static double __ros_log_throttle_last_hit__ = 0.0; \
459  double __ros_log_throttle_now__ = ::ros::Time::now().toSec(); \
460  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROSCONSOLE_THROTTLE_CHECK(__ros_log_throttle_now__, __ros_log_throttle_last_hit__, period))\
461  { \
462  __ros_log_throttle_last_hit__ = __ros_log_throttle_now__; \
463  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
464  } \
465  } while(false)
466 
467 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
475 #define ROS_LOG_STREAM_THROTTLE(period, level, name, args) \
476  do \
477  { \
478  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
479  static double __ros_log_stream_throttle__last_hit__ = 0.0; \
480  double __ros_log_stream_throttle__now__ = ::ros::Time::now().toSec(); \
481  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && \
482  ROSCONSOLE_THROTTLE_CHECK(__ros_log_stream_throttle__now__, __ros_log_stream_throttle__last_hit__, period))\
483  { \
484  __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__; \
485  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
486  } \
487  } while(false)
488 
496 #define ROS_LOG_DELAYED_THROTTLE(period, level, name, ...) \
497  do \
498  { \
499  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
500  double __ros_log_delayed_throttle__now__ = ::ros::Time::now().toSec(); \
501  static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__; \
502  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && \
503  ROSCONSOLE_THROTTLE_CHECK(__ros_log_delayed_throttle__now__, __ros_log_delayed_throttle__last_hit__, period))\
504  { \
505  __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__; \
506  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
507  } \
508  } while(false)
509 
510 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
518 #define ROS_LOG_STREAM_DELAYED_THROTTLE(period, level, name, args) \
519  do \
520  { \
521  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
522  double __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now().toSec(); \
523  static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__; \
524  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && \
525  ROSCONSOLE_THROTTLE_CHECK(__ros_log_stream_delayed_throttle__now__, __ros_log_stream_delayed_throttle__last_hit__, period)) \
526  { \
527  __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__; \
528  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
529  } \
530  } while(false)
531 
539 #define ROS_LOG_FILTER(filter, level, name, ...) \
540  do \
541  { \
542  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
543  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
544  { \
545  ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
546  } \
547  } while(false)
548 
556 #define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
557  do \
558  { \
559  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
560  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
561  { \
562  ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
563  } \
564  } while(false)
565 
572 #define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
573 
579 #define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)
580 
582 
583 #endif // ROSCONSOLE_ROSCONSOLE_H
ROSCONSOLE_DECL void registerLogLocation(LogLocation *loc)
Registers a logging location with the system.
Definition: rosconsole.cpp:622
std::string format_
Definition: console.h:133
log4cxx::LevelPtr g_level_lookup[levels::Count]
virtual bool isEnabled()
Returns whether or not the log statement should be printed. Called before the log arguments are evalu...
Definition: console.h:236
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
Tells the system that a logger&#39;s level has changed.
Definition: rosconsole.cpp:665
Base-class for filters. Filters allow full user-defined control over whether or not a message should ...
Definition: console.h:228
Parameter structure passed to FilterBase::isEnabled(...);. Includes both input and output parameters...
Definition: console.h:191
::ros::console::Level level_
Definition: console.h:265
ROSCONSOLE_DECL void initialize()
Don&#39;t call this directly. Performs any required initialization/configuration. Happens automatically w...
Definition: rosconsole.cpp:403
void * logger
[input/output] Handle identifying logger that this message will be output to. If changed, uses the new logger
Definition: console.h:200
ROSCONSOLE_DECL void setFixedFilterToken(const std::string &key, const std::string &val)
Definition: rosconsole.cpp:95
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
Definition: rosconsole.cpp:705
const char * message
[input] The formatted message that will be output
Definition: console.h:197
ROSCONSOLE_DECL bool g_initialized
Only exported because the macros need it. Do not use directly.
Definition: rosconsole.cpp:59
ROSCONSOLE_DECL std::string formatToString(const char *fmt,...)
Definition: rosconsole.cpp:474
#define ROSCONSOLE_DECL
Definition: console.h:58
ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation *loc)
Internal.
Definition: rosconsole.cpp:659
ROSCONSOLE_DECL void deregister_appender(LogAppender *appender)
Definition: rosconsole.cpp:694
std::string out_message
[output] If set, writes this message instead of the original
Definition: console.h:204
boost::shared_ptr< Token > TokenPtr
Definition: console.h:126
Level level
[input/output] Severity level. If changed, uses the new level
Definition: console.h:201
ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt, va_list args)
Definition: rosconsole.cpp:450
const char * file
[input] File the message came from
Definition: console.h:194
#define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
Definition: console.h:68
ROSCONSOLE_DECL void initializeLogLocation(LogLocation *loc, const std::string &name, Level level)
Internal.
Definition: rosconsole.cpp:634
virtual ~Token()
Definition: console.h:116
ROSCONSOLE_DECL void shutdown()
Definition: rosconsole.cpp:699
std::vector< TokenPtr > V_Token
Definition: console.h:127
int line
[input] Line the message came from
Definition: console.h:195
ROSCONSOLE_DECL std::string g_last_error_message
Only exported because the TopicManager need it. Do not use directly.
Definition: rosconsole.cpp:73
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
Definition: rosconsole.cpp:710
ROSCONSOLE_DECL Formatter g_formatter
Only exported because the implementation need it. Do not use directly.
Definition: rosconsole.cpp:395
ROSCONSOLE_DECL void setLogLocationLevel(LogLocation *loc, Level level)
Internal.
Definition: rosconsole.cpp:653
ROSCONSOLE_DECL void register_appender(LogAppender *appender)
Definition: rosconsole.cpp:689
void print(ros::console::Level level, const std::string &s)
Definition: example.cpp:38
virtual bool isEnabled(FilterParams &)
Returns whether or not the log statement should be printed. Called once the message has been formatte...
Definition: console.h:241
ROSCONSOLE_DECL void formatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt,...)
Definition: rosconsole.cpp:464


rosconsole
Author(s): Josh Faust
autogenerated on Mon Feb 28 2022 23:30:41