Go to the documentation of this file.
33 #ifndef ROSCONSOLE_ROSCONSOLE_H
34 #define ROSCONSOLE_ROSCONSOLE_H
42 #include <ros/macros.h>
46 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
47 #include "log4cxx/level.h"
52 #ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
53 #ifdef rosconsole_EXPORTS // we are building a shared lib/dll
54 #define ROSCONSOLE_DECL ROS_HELPER_EXPORT
55 #else // we are using shared lib/dll
56 #define ROSCONSOLE_DECL ROS_HELPER_IMPORT
58 #else // ros is being built around static libraries
59 #define ROSCONSOLE_DECL
64 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b) __attribute__ ((__format__ (__printf__, a, b)));
68 #ifndef ROSCONSOLE_PRINTF_ATTRIBUTE
69 #define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
74 template<
typename T>
class shared_array;
84 #ifdef ROSCONSOLE_BACKEND_LOG4CXX
130 void init(
const char* fmt);
158 const char* file,
int line,
195 const char*
function;
276 #define ROS_LIKELY(x) (x)
277 #define ROS_UNLIKELY(x) (x)
279 #define ROS_LIKELY(x) __builtin_expect((x),1)
280 #define ROS_UNLIKELY(x) __builtin_expect((x),0)
284 #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
285 #elif defined(__GNUC__)
286 #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
288 #define __ROSCONSOLE_FUNCTION__ ""
292 #ifdef ROS_PACKAGE_NAME
293 #define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
295 #define ROSCONSOLE_PACKAGE_NAME "unknown_package"
298 #define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
299 #define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
300 #define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX
303 #define ROSCONSOLE_SEVERITY_DEBUG 0
304 #define ROSCONSOLE_SEVERITY_INFO 1
305 #define ROSCONSOLE_SEVERITY_WARN 2
306 #define ROSCONSOLE_SEVERITY_ERROR 3
307 #define ROSCONSOLE_SEVERITY_FATAL 4
308 #define ROSCONSOLE_SEVERITY_NONE 5
315 #ifndef ROSCONSOLE_MIN_SEVERITY
316 #define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
323 #define ROSCONSOLE_AUTOINIT
325 #define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
326 ROSCONSOLE_AUTOINIT; \
327 static ::ros::console::LogLocation __rosconsole_define_location__loc = {false, false, ::ros::console::levels::Count, 0}; \
328 if (ROS_UNLIKELY(!__rosconsole_define_location__loc.initialized_)) \
330 initializeLogLocation(&__rosconsole_define_location__loc, name, level); \
332 if (ROS_UNLIKELY(__rosconsole_define_location__loc.level_ != level)) \
334 setLogLocationLevel(&__rosconsole_define_location__loc, level); \
335 checkLogLocationEnabled(&__rosconsole_define_location__loc); \
337 bool __rosconsole_define_location__enabled = __rosconsole_define_location__loc.logger_enabled_ && (cond);
339 #define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
340 ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)
342 #define ROSCONSOLE_PRINT_AT_LOCATION(...) \
343 ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(0, __VA_ARGS__)
346 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
349 std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
350 __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
351 ::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__); \
354 #define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
355 ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(0, args)
366 #define ROS_LOG_COND(cond, level, name, ...) \
369 ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
371 if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
373 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
386 #define ROS_LOG_STREAM_COND(cond, level, name, args) \
389 ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
390 if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
392 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
402 #define ROS_LOG_ONCE(level, name, ...) \
405 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
406 static bool hit = false; \
407 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
410 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
421 #define ROS_LOG_STREAM_ONCE(level, name, args) \
424 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
425 static bool __ros_log_stream_once__hit__ = false; \
426 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
428 __ros_log_stream_once__hit__ = true; \
429 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
440 #define ROS_LOG_THROTTLE(rate, level, name, ...) \
443 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
444 static double last_hit = 0.0; \
445 ::ros::Time now = ::ros::Time::now(); \
446 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(last_hit + rate <= now.toSec())) \
448 last_hit = now.toSec(); \
449 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
461 #define ROS_LOG_STREAM_THROTTLE(rate, level, name, args) \
464 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
465 static double __ros_log_stream_throttle__last_hit__ = 0.0; \
466 ::ros::Time __ros_log_stream_throttle__now__ = ::ros::Time::now(); \
467 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_throttle__last_hit__ + rate <= __ros_log_stream_throttle__now__.toSec())) \
469 __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__.toSec(); \
470 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
481 #define ROS_LOG_DELAYED_THROTTLE(rate, level, name, ...) \
484 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
485 ::ros::Time __ros_log_delayed_throttle__now__ = ::ros::Time::now(); \
486 static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
487 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_delayed_throttle__last_hit__ + rate <= __ros_log_delayed_throttle__now__.toSec())) \
489 __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
490 ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
502 #define ROS_LOG_STREAM_DELAYED_THROTTLE(rate, level, name, args) \
505 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
506 ::ros::Time __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now(); \
507 static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
508 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_delayed_throttle__last_hit__ + rate <= __ros_log_stream_delayed_throttle__now__.toSec())) \
510 __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
511 ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
522 #define ROS_LOG_FILTER(filter, level, name, ...) \
525 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
526 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
528 ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
539 #define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
542 ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
543 if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
545 ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
555 #define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
562 #define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)
564 #include "rosconsole/macros_generated.h"
566 #endif // ROSCONSOLE_ROSCONSOLE_H
virtual bool isEnabled(FilterParams &)
Returns whether or not the log statement should be printed. Called once the message has been formatte...
ROSCONSOLE_DECL void initializeLogLocation(LogLocation *loc, const std::string &name, Level level)
Internal.
ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt, va_list args)
ROSCONSOLE_DECL bool set_logger_level(const std::string &name, levels::Level level)
int line
[input] Line the message came from
ROSCONSOLE_DECL std::string formatToString(const char *fmt,...)
ROSCONSOLE_DECL void setLogLocationLevel(LogLocation *loc, Level level)
Internal.
virtual bool isEnabled()
Returns whether or not the log statement should be printed. Called before the log arguments are evalu...
ROSCONSOLE_DECL void register_appender(LogAppender *appender)
ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation *loc)
Internal.
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
Tells the system that a logger's level has changed.
ROSCONSOLE_DECL void registerLogLocation(LogLocation *loc)
Registers a logging location with the system.
ROSCONSOLE_DECL void shutdown()
std::shared_ptr< Token > TokenPtr
ROSCONSOLE_DECL Formatter g_formatter
Only exported because the implementation need it. Do not use directly.
ROSCONSOLE_DECL void print(FilterBase *filter, void *logger, Level level, const char *file, int line, const char *function, const char *fmt,...) ROSCONSOLE_PRINTF_ATTRIBUTE(7
Don't call this directly. Use the ROS_LOG() macro instead.
virtual void log(::ros::console::Level level, const char *str, const char *file, const char *function, int line)=0
void * logger
[input/output] Handle identifying logger that this message will be output to. If changed,...
ROSCONSOLE_DECL void initialize()
Don't call this directly. Performs any required initialization/configuration. Happens automatically w...
const char * file
[input] File the message came from
Parameter structure passed to FilterBase::isEnabled(...);. Includes both input and output parameters.
ROSCONSOLE_DECL void setFixedFilterToken(const std::string &key, const std::string &val)
std::vector< TokenPtr > V_Token
Level level
[input/output] Severity level. If changed, uses the new level
#define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
::ros::console::Level level_
std::string out_message
[output] If set, writes this message instead of the original
const char * message
[input] The formatted message that will be output
log4cxx::LevelPtr g_level_lookup[levels::Count]
ROSCONSOLE_DECL bool get_loggers(std::map< std::string, levels::Level > &loggers)
ROSCONSOLE_DECL std::string g_last_error_message
Only exported because the macros need it. Do not use directly.
virtual std::string getString(void *, ::ros::console::Level, const char *, const char *, const char *, int)=0
ROSCONSOLE_DECL void formatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt,...)
struct ROSCONSOLE_DECL LogLocation
Base-class for filters. Filters allow full user-defined control over whether or not a message should ...
sick_scan_xd
Author(s): Michael Lehning
, Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:08