This file is indexed.

/usr/include/ros/console.h is in librosconsole-dev 1.13.5+ds1-3.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
/*
 * Copyright (c) 2008, Willow Garage, Inc.
 * All rights reserved.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *
 *     * Redistributions of source code must retain the above copyright
 *       notice, this list of conditions and the following disclaimer.
 *     * Redistributions in binary form must reproduce the above copyright
 *       notice, this list of conditions and the following disclaimer in the
 *       documentation and/or other materials provided with the distribution.
 *     * Neither the name of Willow Garage, Inc. nor the names of its
 *       contributors may be used to endorse or promote products derived from
 *       this software without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 */

// Author: Josh Faust

#ifndef ROSCONSOLE_ROSCONSOLE_H
#define ROSCONSOLE_ROSCONSOLE_H

#include "console_backend.h"

#include <cstdio>
#include <sstream>
#include <ros/time.h>
#include <cstdarg>
#include <ros/macros.h>
#include <map>
#include <vector>

#ifdef ROSCONSOLE_BACKEND_LOG4CXX
#include "log4cxx/level.h"
#endif

// Import/export for windows dll's and visibility for gcc shared libraries.

#ifdef ROS_BUILD_SHARED_LIBS // ros is being built around shared libraries
  #ifdef rosconsole_EXPORTS // we are building a shared lib/dll
    #define ROSCONSOLE_DECL ROS_HELPER_EXPORT
  #else // we are using shared lib/dll
    #define ROSCONSOLE_DECL ROS_HELPER_IMPORT
  #endif
#else // ros is being built around static libraries
  #define ROSCONSOLE_DECL
#endif

#ifdef __GNUC__
#if __GNUC__ >= 3
#define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b) __attribute__ ((__format__ (__printf__, a, b)))
#endif
#endif

#ifndef ROSCONSOLE_PRINTF_ATTRIBUTE
#define ROSCONSOLE_PRINTF_ATTRIBUTE(a, b)
#endif

namespace boost
{
template<typename T> class shared_array;
}

namespace ros
{
namespace console
{

ROSCONSOLE_DECL void shutdown();

#ifdef ROSCONSOLE_BACKEND_LOG4CXX
extern ROSCONSOLE_DECL log4cxx::LevelPtr g_level_lookup[];
#endif

extern ROSCONSOLE_DECL bool get_loggers(std::map<std::string, levels::Level>& loggers);
extern ROSCONSOLE_DECL bool set_logger_level(const std::string& name, levels::Level level);

/**
 * \brief Only exported because the macros need it.  Do not use directly.
 */
extern ROSCONSOLE_DECL bool g_initialized;

/**
 * \brief Only exported because the TopicManager need it.  Do not use directly.
 */
extern ROSCONSOLE_DECL std::string g_last_error_message;

class LogAppender
{
public:

  virtual ~LogAppender() {}

  virtual void log(::ros::console::Level level, const char* str, const char* file, const char* function, int line) = 0;

};

ROSCONSOLE_DECL void register_appender(LogAppender* appender);

struct Token
{
  virtual ~Token() {}
  /*
   * @param level
   * @param message
   * @param file
   * @param function
   * @param  line
   */
  virtual std::string getString(void*, ::ros::console::Level, const char*, const char*, const char*, int) = 0;
};
typedef boost::shared_ptr<Token> TokenPtr;
typedef std::vector<TokenPtr> V_Token;

struct Formatter
{
  void init(const char* fmt);
  void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
  std::string format_;
  V_Token tokens_;
};

/**
 * \brief Only exported because the implementation need it.  Do not use directly.
 */
extern ROSCONSOLE_DECL Formatter g_formatter;

/**
 * \brief Don't call this directly.  Performs any required initialization/configuration.  Happens automatically when using the macro API.
 *
 * If you're going to be using log4cxx or any of the ::ros::console functions, and need the system to be initialized, use the
 * ROSCONSOLE_AUTOINIT macro.
 */
ROSCONSOLE_DECL void initialize();

class FilterBase;
/**
 * \brief Don't call this directly.  Use the ROS_LOG() macro instead.
 * @param level Logging level
 * @param file File this logging statement is from (usually generated with __FILE__)
 * @param line Line of code this logging statement is from (usually generated with __LINE__)
 * @param fmt Format string
 */
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, 8);

ROSCONSOLE_DECL void print(FilterBase* filter, void* logger, Level level,
	   const std::stringstream& str, const char* file, int line, const char* function);

struct ROSCONSOLE_DECL LogLocation;

/**
 * \brief Registers a logging location with the system.
 *
 * This is used for the case where a logger's verbosity level changes, and we need to reset the enabled status of
 * all the logging statements.
 * @param loc The location to add
 */
ROSCONSOLE_DECL void registerLogLocation(LogLocation* loc);

/**
 * \brief Tells the system that a logger's level has changed
 *
 * This must be called if a log4cxx::Logger's level has been changed in the middle of an application run.
 * Because of the way the static guard for enablement works, if a logger's level is changed and this
 * function is not called, only logging statements which are first hit *after* the change will be correct wrt
 * that logger.
 */
ROSCONSOLE_DECL void notifyLoggerLevelsChanged();

ROSCONSOLE_DECL void setFixedFilterToken(const std::string& key, const std::string& val);

/**
 * \brief Parameter structure passed to FilterBase::isEnabled(...);.  Includes both input and output parameters
 */
struct FilterParams
{
  // input parameters
  const char* file;                         ///< [input] File the message came from
  int line;                                 ///< [input] Line the message came from
  const char* function;                     ///< [input] Function the message came from
  const char* message;                      ///< [input] The formatted message that will be output

  // input/output parameters
  void* logger;                             ///< [input/output] Handle identifying logger that this message will be output to.  If changed, uses the new logger
  Level level;                              ///< [input/output] Severity level.  If changed, uses the new level

  // output parameters
  std::string out_message;                  ///< [output] If set, writes this message instead of the original
};

/**
 * \brief Base-class for filters.  Filters allow full user-defined control over whether or not a message should print.
 * The ROS_X_FILTER... macros provide the filtering functionality.
 *
 * Filters get a chance to veto the message from printing at two times: first before the message arguments are
 * evaluated and the message is formatted, and then once the message is formatted before it is printed.  It is also possible
 * to change the message, logger and severity level at this stage (see the FilterParams struct for more details).
 *
 * When a ROS_X_FILTER... macro is called, here is the high-level view of how it uses the filter passed in:
\verbatim
if (<logging level is enabled> && filter->isEnabled())
{
  <format message>
  <fill out FilterParams>
  if (filter->isEnabled(params))
  {
    <print message>
  }
}
\endverbatim
 */
class FilterBase
{
public:
  virtual ~FilterBase() {}
  /**
   * \brief Returns whether or not the log statement should be printed.  Called before the log arguments are evaluated
   * and the message is formatted.
   */
  inline virtual bool isEnabled() { return true; }
  /**
   * \brief Returns whether or not the log statement should be printed.  Called once the message has been formatted,
   * and allows you to change the message, logger and severity level if necessary.
   */
  inline virtual bool isEnabled(FilterParams&) { return true; }
};

struct ROSCONSOLE_DECL LogLocation;
/**
 * \brief Internal
 */
ROSCONSOLE_DECL void initializeLogLocation(LogLocation* loc, const std::string& name, Level level);
/**
 * \brief Internal
 */
ROSCONSOLE_DECL void setLogLocationLevel(LogLocation* loc, Level level);
/**
 * \brief Internal
 */
ROSCONSOLE_DECL void checkLogLocationEnabled(LogLocation* loc);

/**
 * \brief Internal
 */
struct LogLocation
{
  bool initialized_;
  bool logger_enabled_;
  ::ros::console::Level level_;
  void* logger_;
};

ROSCONSOLE_DECL void vformatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, va_list args);
ROSCONSOLE_DECL void formatToBuffer(boost::shared_array<char>& buffer, size_t& buffer_size, const char* fmt, ...);
ROSCONSOLE_DECL std::string formatToString(const char* fmt, ...);

} // namespace console
} // namespace ros

#ifdef WIN32
#define ROS_LIKELY(x)       (x)
#define ROS_UNLIKELY(x)     (x)
#else
#define ROS_LIKELY(x)       __builtin_expect((x),1)
#define ROS_UNLIKELY(x)     __builtin_expect((x),0)
#endif

#if defined(MSVC)
  #define __ROSCONSOLE_FUNCTION__ __FUNCSIG__
#elif defined(__GNUC__)
  #define __ROSCONSOLE_FUNCTION__ __PRETTY_FUNCTION__
#else
  #define __ROSCONSOLE_FUNCTION__ ""
#endif


#ifdef ROS_PACKAGE_NAME
#define ROSCONSOLE_PACKAGE_NAME ROS_PACKAGE_NAME
#else
#define ROSCONSOLE_PACKAGE_NAME "unknown_package"
#endif

#define ROSCONSOLE_ROOT_LOGGER_NAME "ros"
#define ROSCONSOLE_NAME_PREFIX ROSCONSOLE_ROOT_LOGGER_NAME "." ROSCONSOLE_PACKAGE_NAME
#define ROSCONSOLE_DEFAULT_NAME ROSCONSOLE_NAME_PREFIX

// These allow you to compile-out everything below a certain severity level if necessary
#define ROSCONSOLE_SEVERITY_DEBUG 0
#define ROSCONSOLE_SEVERITY_INFO 1
#define ROSCONSOLE_SEVERITY_WARN 2
#define ROSCONSOLE_SEVERITY_ERROR 3
#define ROSCONSOLE_SEVERITY_FATAL 4
#define ROSCONSOLE_SEVERITY_NONE 5

/**
 * \def ROSCONSOLE_MIN_SEVERITY
 *
 * Define ROSCONSOLE_MIN_SEVERITY=ROSCONSOLE_SEVERITY_[DEBUG|INFO|WARN|ERROR|FATAL] in your build options to compile out anything below that severity
 */
#ifndef ROSCONSOLE_MIN_SEVERITY
#define ROSCONSOLE_MIN_SEVERITY ROSCONSOLE_SEVERITY_DEBUG
#endif

/**
 * \def ROSCONSOLE_AUTOINIT
 * \brief Initializes the rosconsole library.  Usually unnecessary to call directly.
 */
#define ROSCONSOLE_AUTOINIT \
  do \
  { \
    if (ROS_UNLIKELY(!::ros::console::g_initialized)) \
    { \
      ::ros::console::initialize(); \
    } \
  } while(false)

#define ROSCONSOLE_DEFINE_LOCATION(cond, level, name) \
  ROSCONSOLE_AUTOINIT; \
  static ::ros::console::LogLocation __rosconsole_define_location__loc = {false, false, ::ros::console::levels::Count, 0}; /* Initialized at compile-time */ \
  if (ROS_UNLIKELY(!__rosconsole_define_location__loc.initialized_)) \
  { \
    initializeLogLocation(&__rosconsole_define_location__loc, name, level); \
  } \
  if (ROS_UNLIKELY(__rosconsole_define_location__loc.level_ != level)) \
  { \
    setLogLocationLevel(&__rosconsole_define_location__loc, level); \
    checkLogLocationEnabled(&__rosconsole_define_location__loc); \
  } \
  bool __rosconsole_define_location__enabled = __rosconsole_define_location__loc.logger_enabled_ && (cond);

#define ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, ...) \
    ::ros::console::print(filter, __rosconsole_define_location__loc.logger_, __rosconsole_define_location__loc.level_, __FILE__, __LINE__, __ROSCONSOLE_FUNCTION__, __VA_ARGS__)

#define ROSCONSOLE_PRINT_AT_LOCATION(...) \
    ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(0, __VA_ARGS__)

// inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
#define ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args) \
  do \
  { \
    std::stringstream __rosconsole_print_stream_at_location_with_filter__ss__; \
    __rosconsole_print_stream_at_location_with_filter__ss__ << args; \
    ::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__); \
  } while (0)

#define ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args) \
    ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(0, args)

/**
 * \brief Log to a given named logger at a given verbosity level, only if a given condition has been met, with printf-style formatting
 *
 * \note The condition will only be evaluated if this logging statement is enabled
 *
 * \param cond Boolean condition to be evaluated
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_COND(cond, level, name, ...) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
    \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
    { \
      ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, only if a given condition has been met, with stream-style formatting
 *
 * \note The condition will only be evaluated if this logging statement is enabled
 *
 * \param cond Boolean condition to be evaluated
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_STREAM_COND(cond, level, name, args) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(cond, level, name); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled)) \
    { \
      ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, only the first time it is hit when enabled, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_ONCE(level, name, ...) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    static bool hit = false; \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!hit)) \
    { \
      hit = true; \
      ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
    } \
  } while(false)

// inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
/**
 * \brief Log to a given named logger at a given verbosity level, only the first time it is hit when enabled, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_STREAM_ONCE(level, name, args) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    static bool __ros_log_stream_once__hit__ = false; \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(!__ros_log_stream_once__hit__)) \
    { \
      __ros_log_stream_once__hit__ = true; \
      ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 * \param rate The rate it should actually trigger at
 */
#define ROS_LOG_THROTTLE(rate, level, name, ...) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    static double last_hit = 0.0; \
    ::ros::Time now = ::ros::Time::now(); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(last_hit + rate <= now.toSec())) \
    { \
      last_hit = now.toSec(); \
      ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
    } \
  } while(false)

// inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
/**
 * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 * \param rate The rate it should actually trigger at
 */
#define ROS_LOG_STREAM_THROTTLE(rate, level, name, args) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    static double __ros_log_stream_throttle__last_hit__ = 0.0; \
    ::ros::Time __ros_log_stream_throttle__now__ = ::ros::Time::now(); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_throttle__last_hit__ + rate <= __ros_log_stream_throttle__now__.toSec())) \
    { \
      __ros_log_stream_throttle__last_hit__ = __ros_log_stream_throttle__now__.toSec(); \
      ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 * \param rate The rate it should actually trigger at
 */
#define ROS_LOG_DELAYED_THROTTLE(rate, level, name, ...) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    ::ros::Time __ros_log_delayed_throttle__now__ = ::ros::Time::now(); \
    static double __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_delayed_throttle__last_hit__ + rate <= __ros_log_delayed_throttle__now__.toSec())) \
    { \
      __ros_log_delayed_throttle__last_hit__ = __ros_log_delayed_throttle__now__.toSec(); \
      ROSCONSOLE_PRINT_AT_LOCATION(__VA_ARGS__); \
    } \
  } while(false)

// inside a macro which uses args use only well namespaced variable names in order to not overlay variables coming in via args
/**
 * \brief Log to a given named logger at a given verbosity level, limited to a specific rate of printing and postponed first message
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 * \param rate The rate it should actually trigger at, and the delay before which no message will be shown.
 */
#define ROS_LOG_STREAM_DELAYED_THROTTLE(rate, level, name, args) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    ::ros::Time __ros_log_stream_delayed_throttle__now__ = ::ros::Time::now(); \
    static double __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && ROS_UNLIKELY(__ros_log_stream_delayed_throttle__last_hit__ + rate <= __ros_log_stream_delayed_throttle__now__.toSec())) \
    { \
      __ros_log_stream_delayed_throttle__last_hit__ = __ros_log_stream_delayed_throttle__now__.toSec(); \
      ROSCONSOLE_PRINT_STREAM_AT_LOCATION(args); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, with user-defined filtering, with printf-style formatting
 *
 * \param filter pointer to the filter to be used
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_FILTER(filter, level, name, ...) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
    { \
      ROSCONSOLE_PRINT_AT_LOCATION_WITH_FILTER(filter, __VA_ARGS__); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, with user-defined filtering, with stream-style formatting
 *
 * \param cond Boolean condition to be evaluated
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_STREAM_FILTER(filter, level, name, args) \
  do \
  { \
    ROSCONSOLE_DEFINE_LOCATION(true, level, name); \
    if (ROS_UNLIKELY(__rosconsole_define_location__enabled) && (filter)->isEnabled()) \
    { \
      ROSCONSOLE_PRINT_STREAM_AT_LOCATION_WITH_FILTER(filter, args); \
    } \
  } while(false)

/**
 * \brief Log to a given named logger at a given verbosity level, with printf-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG(level, name, ...) ROS_LOG_COND(true, level, name, __VA_ARGS__)
/**
 * \brief Log to a given named logger at a given verbosity level, with stream-style formatting
 *
 * \param level One of the levels specified in ::ros::console::levels::Level
 * \param name Name of the logger.  Note that this is the fully qualified name, and does NOT include "ros.<package_name>".  Use ROSCONSOLE_DEFAULT_NAME if you would like to use the default name.
 */
#define ROS_LOG_STREAM(level, name, args) ROS_LOG_STREAM_COND(true, level, name, args)

#include "rosconsole/macros_generated.h"

#endif // ROSCONSOLE_ROSCONSOLE_H