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 
112 struct Token
113 {
114  virtual ~Token() {}
115  /*
116  * @param level
117  * @param message
118  * @param file
119  * @param function
120  * @param line
121  */
122  virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int) = 0;
123 };
125 typedef std::vector<TokenPtr> V_Token;
126 
127 struct Formatter
128 {
129  void init(const char* fmt);
130  void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
131  std::string format_;
132  V_Token tokens_;
133 };
134 
139 
147 
148 class FilterBase;
156 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
157  const char* file, int line,
158  const char* function, const char* fmt, ...) ROSCONSOLE_PRINTF_ATTRIBUTE(7, 8);
159 
160 ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
161  const std::stringstream& str, const char* file, int line, const char* function);
162 
164 
172 ROSCONSOLE_DECL void registerLogLocation(LogLocation* loc);
173 
183 
184 ROSCONSOLE_DECL void setFixedFilterToken(const std::string& key, const std::string& val);
185 
190 {
191  // input parameters
192  const char* file;
193  int line;
194  const char* function;
195  const char* message;
196 
197  // input/output parameters
198  void* logger;
200 
201  // output parameters
202  std::string out_message;
203 };
204 
227 {
228 public:
229  virtual ~FilterBase() {}
234  inline virtual bool isEnabled() { return true; }
239  inline virtual bool isEnabled(FilterParams&) { return true; }
240 };
241 
242 struct ROSCONSOLE_DECL LogLocation;
246 ROSCONSOLE_DECL void initializeLogLocation(LogLocation* loc, const std::string& name, Level level);
250 ROSCONSOLE_DECL void setLogLocationLevel(LogLocation* loc, Level level);
254 ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation* loc);
255 
259 struct LogLocation
260 {
264  void* logger_;
265 };
266 
267 ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args);
268 ROSCONSOLE_DECL void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...);
269 ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);
270 
271 } // namespace console
272 } // namespace ros
273 
274 #ifdef WIN32
275 #define ROS_LIKELY(x) (x)
276 #define ROS_UNLIKELY(x) (x)
277 #else
278 #define ROS_LIKELY(x) __builtin_expect((x),1)
279 #define ROS_UNLIKELY(x) __builtin_expect((x),0)
280 #endif
281 
282 #if defined(MSVC)
283  #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
284 #elif defined(__GNUC__)
285  #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
286 #else
287  #define __ROSCONSOLE_FUNCTION__ ""
288 #endif
289 
290 
291 #ifdef ROS_PACKAGE_NAME
292 #define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
293 #else
294 #define ROSCONSOLE_PACKAGE_NAME "unknown_package"
295 #endif
296 
297 #define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
298 #define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
299 #define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX
300 
301 // These allow you to compile-out everything below a certain severity level if necessary
302 #define ROSCONSOLE_SEVERITY_DEBUG 0
303 #define ROSCONSOLE_SEVERITY_INFO 1
304 #define ROSCONSOLE_SEVERITY_WARN 2
305 #define ROSCONSOLE_SEVERITY_ERROR 3
306 #define ROSCONSOLE_SEVERITY_FATAL 4
307 #define ROSCONSOLE_SEVERITY_NONE 5
308 
314 #ifndef ROSCONSOLE_MIN_SEVERITY
315 #define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
316 #endif
317 
322 #define ROSCONSOLE_AUTOINIT \
323  do \
324  { \
325  if (ROS_UNLIKELY(!::ros::console::g_initialized)) \
326  { \
327  ::ros::console::initialize(); \
328  } \
329  } while(false)
330 
331 #define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
332  ROSCONSOLE_AUTOINIT; \
333  static ::ros::console::LogLocation __rosconsole_define_location__loc = {false, false, ::ros::console::levels::Count, NULL}; /* Initialized at compile-time */ \
334  if (ROS_UNLIKELY(!__rosconsole_define_location__loc.initialized_)) \
335  { \
336  initializeLogLocation(&__rosconsole_define_location__loc, name, level); \
337  } \
338  if (ROS_UNLIKELY(__rosconsole_define_location__loc.level_ != level)) \
339  { \
340  setLogLocationLevel(&__rosconsole_define_location__loc, level); \
341  checkLogLocationEnabled(&__rosconsole_define_location__loc); \
342  } \
343  bool __rosconsole_define_location__enabled = __rosconsole_define_location__loc.logger_enabled_ && (cond);
344 
345 #define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
346  ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)
347 
348 #define ROSCONSOLE_PRINT_AT_LOCATION(...) \
349  ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(NULL, __VA_ARGS__)
350 
351 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
352 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
353  do \
354  { \
355  std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
356  __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
357  ::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__); \
358  } while (0)
359 
360 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
361  ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(NULL, args)
362 
372 #define ROS_LOG_COND(cond, level, name, ...) \
373  do \
374  { \
375  ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
376  \
377  if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
378  { \
379  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
380  } \
381  } while(false)
382 
392 #define ROS_LOG_STREAM_COND(cond, level, name, args) \
393  do \
394  { \
395  ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
396  if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
397  { \
398  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
399  } \
400  } while(false)
401 
408 #define ROS_LOG_ONCE(level, name, ...) \
409  do \
410  { \
411  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
412  static bool hit = false; \
413  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
414  { \
415  hit = true; \
416  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
417  } \
418  } while(false)
419 
420 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
427 #define ROS_LOG_STREAM_ONCE(level, name, args) \
428  do \
429  { \
430  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
431  static bool __ros_log_stream_once__hit__ = false; \
432  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
433  { \
434  __ros_log_stream_once__hit__ = true; \
435  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
436  } \
437  } while(false)
438 
446 #define ROS_LOG_THROTTLE(rate, level, name, ...) \
447  do \
448  { \
449  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
450  static double last_hit = 0.0; \
451  ::ros::Time now = ::ros::Time::now(); \
452  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(last_hit + rate <= now.toSec())) \
453  { \
454  last_hit = now.toSec(); \
455  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
456  } \
457  } while(false)
458 
459 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
467 #define ROS_LOG_STREAM_THROTTLE(rate, level, name, args) \
468  do \
469  { \
470  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
471  static double __ros_log_stream_throttle__last_hit__ = 0.0; \
472  ::ros::Time __ros_log_stream_throttle__now__ = ::ros::Time::now(); \
473  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_throttle__last_hit__ + rate <= __ros_log_stream_throttle__now__.toSec())) \
474  { \
475  __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__.toSec(); \
476  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
477  } \
478  } while(false)
479 
487 #define ROS_LOG_DELAYED_THROTTLE(rate, level, name, ...) \
488  do \
489  { \
490  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
491  ::ros::Time __ros_log_delayed_throttle__now__ = ::ros::Time::now(); \
492  static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
493  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_delayed_throttle__last_hit__ + rate <= __ros_log_delayed_throttle__now__.toSec())) \
494  { \
495  __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
496  ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
497  } \
498  } while(false)
499 
500 // inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
508 #define ROS_LOG_STREAM_DELAYED_THROTTLE(rate, level, name, args) \
509  do \
510  { \
511  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
512  ::ros::Time __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now(); \
513  static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
514  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_delayed_throttle__last_hit__ + rate <= __ros_log_stream_delayed_throttle__now__.toSec())) \
515  { \
516  __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
517  ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
518  } \
519  } while(false)
520 
528 #define ROS_LOG_FILTER(filter, level, name, ...) \
529  do \
530  { \
531  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
532  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
533  { \
534  ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
535  } \
536  } while(false)
537 
545 #define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
546  do \
547  { \
548  ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
549  if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
550  { \
551  ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
552  } \
553  } while(false)
554 
561 #define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
562 
568 #define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)
569 
571 
572 #endif // ROSCONSOLE_ROSCONSOLE_H
ROSCONSOLE_DECL void registerLogLocation(LogLocation *loc)
Registers a logging location with the system.
Definition: rosconsole.cpp:618
std::string format_
Definition: console.h:131
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:234
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
Tells the system that a logger&#39;s level has changed.
Definition: rosconsole.cpp:661
Base-class for filters. Filters allow full user-defined control over whether or not a message should ...
Definition: console.h:226
Parameter structure passed to FilterBase::isEnabled(...);. Includes both input and output parameters...
Definition: console.h:189
::ros::console::Level level_
Definition: console.h:263
ROSCONSOLE_DECL void initialize()
Don&#39;t call this directly. Performs any required initialization/configuration. Happens automatically w...
Definition: rosconsole.cpp:406
void * logger
[input/output] Handle identifying logger that this message will be output to. If changed, uses the new logger
Definition: console.h:198
ROSCONSOLE_DECL void setFixedFilterToken(const std::string &key, const std::string &val)
Definition: rosconsole.cpp:113
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
Definition: rosconsole.cpp:696
const char * message
[input] The formatted message that will be output
Definition: console.h:195
ROSCONSOLE_DECL bool g_initialized
Only exported because the macros need it. Do not use directly.
Definition: rosconsole.cpp:81
ROSCONSOLE_DECL std::string formatToString(const char *fmt,...)
Definition: rosconsole.cpp:470
#define ROSCONSOLE_DECL
Definition: console.h:58
ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation *loc)
Internal.
Definition: rosconsole.cpp:655
std::string out_message
[output] If set, writes this message instead of the original
Definition: console.h:202
boost::shared_ptr< Token > TokenPtr
Definition: console.h:124
Level level
[input/output] Severity level. If changed, uses the new level
Definition: console.h:199
ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt, va_list args)
Definition: rosconsole.cpp:433
const char * file
[input] File the message came from
Definition: console.h:192
#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:630
virtual ~Token()
Definition: console.h:114
ROSCONSOLE_DECL void shutdown()
Definition: rosconsole.cpp:690
std::vector< TokenPtr > V_Token
Definition: console.h:125
int line
[input] Line the message came from
Definition: console.h:193
ROSCONSOLE_DECL std::string g_last_error_message
Only exported because the TopicManager need it. Do not use directly.
Definition: rosconsole.cpp:95
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
Definition: rosconsole.cpp:701
ROSCONSOLE_DECL Formatter g_formatter
Only exported because the implementation need it. Do not use directly.
Definition: rosconsole.cpp:398
ROSCONSOLE_DECL void setLogLocationLevel(LogLocation *loc, Level level)
Internal.
Definition: rosconsole.cpp:649
ROSCONSOLE_DECL void register_appender(LogAppender *appender)
Definition: rosconsole.cpp:685
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:239
ROSCONSOLE_DECL void formatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt,...)
Definition: rosconsole.cpp:460


rosconsole
Author(s): Josh Faust
autogenerated on Mon Nov 2 2020 03:52:16