This commit is contained in:
Ivan
2022-04-05 11:42:28 +03:00
commit 6dc0eb0fcf
5565 changed files with 1200500 additions and 0 deletions

View File

@@ -0,0 +1,155 @@
/*
* 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_ROSASSERT_H
#define ROSCONSOLE_ROSASSERT_H
#include "ros/console.h"
#include "ros/static_assert.h"
/** \file */
/** \def ROS_ASSERT(cond)
* \brief Asserts that the provided condition evaluates to true.
*
* If it is false, program execution will abort, with an informative
* statement about which assertion failed, in what file. Use ROS_ASSERT
* instead of assert() itself.
*
* If running inside a debugger, ROS_ASSERT will allow you to step past the assertion.
*/
/** \def ROS_ASSERT_MSG(cond, ...)
* \brief Asserts that the provided condition evaluates to true.
*
* If it is false, program execution will abort, with an informative
* statement about which assertion failed, in what file, and it will print out
* a printf-style message you define. Example usage:
@verbatim
ROS_ASSERT_MSG(x > 0, "Uh oh, x went negative. Value = %d", x);
@endverbatim
*
* If running inside a debugger, ROS_ASSERT will allow you to step past the assertion.
*/
/**
* \def ROS_ASSERT_CMD()
* \brief Runs a command if the provided condition is false
*
* For example:
\verbatim
ROS_ASSERT_CMD(x > 0, handleError(...));
\endverbatim
*/
/** \def ROS_BREAK()
* \brief Aborts program execution.
*
* Aborts program execution with an informative message stating what file and
* line it was called from. Use ROS_BREAK instead of calling assert(0) or
* ROS_ASSERT(0).
*
* If running inside a debugger, ROS_BREAK will allow you to step past the breakpoint.
*/
/** \def ROS_ISSUE_BREAK()
* \brief Always issues a breakpoint instruction.
*
* This define is mostly for internal use, but is useful if you want to simply issue a break
* instruction in a cross-platform way.
*
* Currently implemented for Windows (any platform), powerpc64, and x86
*/
#include <ros/platform.h>
#ifdef WIN32
# if defined (__MINGW32__)
# define ROS_ISSUE_BREAK() DebugBreak();
# else // MSVC
# define ROS_ISSUE_BREAK() __debugbreak();
# endif
#elif defined(__powerpc64__)
# define ROS_ISSUE_BREAK() asm volatile ("tw 31,1,1");
#elif defined(__i386__) || defined(__ia64__) || defined(__x86_64__)
# define ROS_ISSUE_BREAK() asm("int $3");
#else
# include <stdlib.h>
# define ROS_ISSUE_BREAK() abort();
#endif
#ifndef NDEBUG
#ifndef ROS_ASSERT_ENABLED
#define ROS_ASSERT_ENABLED
#endif
#endif
#ifdef ROS_ASSERT_ENABLED
#define ROS_BREAK() \
do { \
ROS_FATAL("BREAKPOINT HIT\n\tfile = %s\n\tline=%d\n", __FILE__, __LINE__); \
ROS_ISSUE_BREAK() \
} while (false)
#define ROS_ASSERT(cond) \
do { \
if (!(cond)) { \
ROS_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n", __FILE__, __LINE__, #cond); \
ROS_ISSUE_BREAK() \
} \
} while (false)
#define ROS_ASSERT_MSG(cond, ...) \
do { \
if (!(cond)) { \
ROS_FATAL("ASSERTION FAILED\n\tfile = %s\n\tline = %d\n\tcond = %s\n\tmessage = ", __FILE__, __LINE__, #cond); \
ROS_FATAL(__VA_ARGS__); \
ROS_FATAL("\n"); \
ROS_ISSUE_BREAK(); \
} \
} while (false)
#define ROS_ASSERT_CMD(cond, cmd) \
do { \
if (!(cond)) { \
cmd; \
} \
} while (false)
#else
#define ROS_BREAK()
#define ROS_ASSERT(cond)
#define ROS_ASSERT_MSG(cond, ...)
#define ROS_ASSERT_CMD(cond, cmd)
#endif
#endif // ROSCONSOLE_ROSASSERT_H

View File

@@ -0,0 +1,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

View File

@@ -0,0 +1,68 @@
/*
* Copyright (c) 2013, Open Source Robotics Foundation
* 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 the 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.
*/
#ifndef ROSCONSOLE_CONSOLE_BACKEND_H
#define ROSCONSOLE_CONSOLE_BACKEND_H
namespace ros
{
namespace console
{
namespace levels
{
enum Level
{
Debug,
Info,
Warn,
Error,
Fatal,
Count
};
}
typedef levels::Level Level;
namespace backend
{
void notifyLoggerLevelsChanged();
extern void (*function_notifyLoggerLevelsChanged)();
void print(void* logger_handle, ::ros::console::Level level, const char* str, const char* file, const char* function, int line);
extern void (*function_print)(void*, ::ros::console::Level, const char*, const char*, const char*, int);
} // namespace backend
} // namespace console
} // namespace ros
#endif // ROSCONSOLE_CONSOLE_BACKEND_H

View File

@@ -0,0 +1,70 @@
/*
* 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_STATIC_ASSERT_H
#define ROSCONSOLE_STATIC_ASSERT_H
// boost's static assert provides better errors messages in the failure case when using
// in templated situations
#include <boost/static_assert.hpp>
/**
* \def ROS_COMPILE_ASSERT(cond)
* \brief Compile-time assert.
*
* Only works with compile time statements, ie:
@verbatim
struct A
{
uint32_t a;
};
ROS_COMPILE_ASSERT(sizeof(A) == 4);
@endverbatim
*/
#define ROS_COMPILE_ASSERT(cond) BOOST_STATIC_ASSERT(cond)
/**
* \def ROS_STATIC_ASSERT(cond)
* \brief Compile-time assert.
*
* Only works with compile time statements, ie:
@verbatim
struct A
{
uint32_t a;
};
ROS_STATIC_ASSERT(sizeof(A) == 4);
@endverbatim
*/
#define ROS_STATIC_ASSERT(cond) BOOST_STATIC_ASSERT(cond)
#endif // ROSCONSOLE_STATIC_ASSERT_H

View File

@@ -0,0 +1,291 @@
// !!!!!!!!!!!!!!!!!!!!!!! This is a generated file, do not edit manually
/*
* 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.
*/
#if (ROSCONSOLE_MIN_SEVERITY > ROSCONSOLE_SEVERITY_DEBUG)
#define ROS_DEBUG(...)
#define ROS_DEBUG_STREAM(args)
#define ROS_DEBUG_NAMED(name, ...)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_DEBUG_COND(cond, ...)
#define ROS_DEBUG_STREAM_COND(cond, args)
#define ROS_DEBUG_COND_NAMED(cond, name, ...)
#define ROS_DEBUG_STREAM_COND_NAMED(cond, name, args)
#define ROS_DEBUG_ONCE(...)
#define ROS_DEBUG_STREAM_ONCE(args)
#define ROS_DEBUG_ONCE_NAMED(name, ...)
#define ROS_DEBUG_STREAM_ONCE_NAMED(name, args)
#define ROS_DEBUG_THROTTLE(rate, ...)
#define ROS_DEBUG_STREAM_THROTTLE(rate, args)
#define ROS_DEBUG_THROTTLE_NAMED(rate, name, ...)
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_DEBUG_DELAYED_THROTTLE(rate, ...)
#define ROS_DEBUG_STREAM_DELAYED_THROTTLE(rate, args)
#define ROS_DEBUG_DELAYED_THROTTLE_NAMED(rate, name, ...)
#define ROS_DEBUG_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
#define ROS_DEBUG_FILTER(filter, ...)
#define ROS_DEBUG_STREAM_FILTER(filter, args)
#define ROS_DEBUG_FILTER_NAMED(filter, name, ...)
#define ROS_DEBUG_STREAM_FILTER_NAMED(filter, name, args)
#else
#define ROS_DEBUG(...) ROS_LOG(::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM(args) ROS_LOG_STREAM(::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_NAMED(name, ...) ROS_LOG(::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_NAMED(name, args) ROS_LOG_STREAM(::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_DEBUG_COND(cond, ...) ROS_LOG_COND(cond, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_DEBUG_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_DEBUG_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_DEBUG_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_DEBUG_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_DEBUG_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Debug, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_DEBUG_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_DEBUG_STREAM_FILTER_NAMED(filter, name, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Debug, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#endif
#if (ROSCONSOLE_MIN_SEVERITY > ROSCONSOLE_SEVERITY_INFO)
#define ROS_INFO(...)
#define ROS_INFO_STREAM(args)
#define ROS_INFO_NAMED(name, ...)
#define ROS_INFO_STREAM_NAMED(name, args)
#define ROS_INFO_COND(cond, ...)
#define ROS_INFO_STREAM_COND(cond, args)
#define ROS_INFO_COND_NAMED(cond, name, ...)
#define ROS_INFO_STREAM_COND_NAMED(cond, name, args)
#define ROS_INFO_ONCE(...)
#define ROS_INFO_STREAM_ONCE(args)
#define ROS_INFO_ONCE_NAMED(name, ...)
#define ROS_INFO_STREAM_ONCE_NAMED(name, args)
#define ROS_INFO_THROTTLE(rate, ...)
#define ROS_INFO_STREAM_THROTTLE(rate, args)
#define ROS_INFO_THROTTLE_NAMED(rate, name, ...)
#define ROS_INFO_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_INFO_DELAYED_THROTTLE(rate, ...)
#define ROS_INFO_STREAM_DELAYED_THROTTLE(rate, args)
#define ROS_INFO_DELAYED_THROTTLE_NAMED(rate, name, ...)
#define ROS_INFO_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
#define ROS_INFO_FILTER(filter, ...)
#define ROS_INFO_STREAM_FILTER(filter, args)
#define ROS_INFO_FILTER_NAMED(filter, name, ...)
#define ROS_INFO_STREAM_FILTER_NAMED(filter, name, args)
#else
#define ROS_INFO(...) ROS_LOG(::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM(args) ROS_LOG_STREAM(::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_NAMED(name, ...) ROS_LOG(::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_NAMED(name, args) ROS_LOG_STREAM(::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_INFO_COND(cond, ...) ROS_LOG_COND(cond, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_INFO_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_INFO_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_INFO_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_INFO_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_INFO_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Info, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_INFO_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_INFO_STREAM_FILTER_NAMED(filter, name, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Info, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#endif
#if (ROSCONSOLE_MIN_SEVERITY > ROSCONSOLE_SEVERITY_WARN)
#define ROS_WARN(...)
#define ROS_WARN_STREAM(args)
#define ROS_WARN_NAMED(name, ...)
#define ROS_WARN_STREAM_NAMED(name, args)
#define ROS_WARN_COND(cond, ...)
#define ROS_WARN_STREAM_COND(cond, args)
#define ROS_WARN_COND_NAMED(cond, name, ...)
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args)
#define ROS_WARN_ONCE(...)
#define ROS_WARN_STREAM_ONCE(args)
#define ROS_WARN_ONCE_NAMED(name, ...)
#define ROS_WARN_STREAM_ONCE_NAMED(name, args)
#define ROS_WARN_THROTTLE(rate, ...)
#define ROS_WARN_STREAM_THROTTLE(rate, args)
#define ROS_WARN_THROTTLE_NAMED(rate, name, ...)
#define ROS_WARN_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_WARN_DELAYED_THROTTLE(rate, ...)
#define ROS_WARN_STREAM_DELAYED_THROTTLE(rate, args)
#define ROS_WARN_DELAYED_THROTTLE_NAMED(rate, name, ...)
#define ROS_WARN_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
#define ROS_WARN_FILTER(filter, ...)
#define ROS_WARN_STREAM_FILTER(filter, args)
#define ROS_WARN_FILTER_NAMED(filter, name, ...)
#define ROS_WARN_STREAM_FILTER_NAMED(filter, name, args)
#else
#define ROS_WARN(...) ROS_LOG(::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM(args) ROS_LOG_STREAM(::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_NAMED(name, ...) ROS_LOG(::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_NAMED(name, args) ROS_LOG_STREAM(::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_WARN_COND(cond, ...) ROS_LOG_COND(cond, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_WARN_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_WARN_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_WARN_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_WARN_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_WARN_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Warn, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_WARN_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_WARN_STREAM_FILTER_NAMED(filter, name, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Warn, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#endif
#if (ROSCONSOLE_MIN_SEVERITY > ROSCONSOLE_SEVERITY_ERROR)
#define ROS_ERROR(...)
#define ROS_ERROR_STREAM(args)
#define ROS_ERROR_NAMED(name, ...)
#define ROS_ERROR_STREAM_NAMED(name, args)
#define ROS_ERROR_COND(cond, ...)
#define ROS_ERROR_STREAM_COND(cond, args)
#define ROS_ERROR_COND_NAMED(cond, name, ...)
#define ROS_ERROR_STREAM_COND_NAMED(cond, name, args)
#define ROS_ERROR_ONCE(...)
#define ROS_ERROR_STREAM_ONCE(args)
#define ROS_ERROR_ONCE_NAMED(name, ...)
#define ROS_ERROR_STREAM_ONCE_NAMED(name, args)
#define ROS_ERROR_THROTTLE(rate, ...)
#define ROS_ERROR_STREAM_THROTTLE(rate, args)
#define ROS_ERROR_THROTTLE_NAMED(rate, name, ...)
#define ROS_ERROR_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_ERROR_DELAYED_THROTTLE(rate, ...)
#define ROS_ERROR_STREAM_DELAYED_THROTTLE(rate, args)
#define ROS_ERROR_DELAYED_THROTTLE_NAMED(rate, name, ...)
#define ROS_ERROR_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
#define ROS_ERROR_FILTER(filter, ...)
#define ROS_ERROR_STREAM_FILTER(filter, args)
#define ROS_ERROR_FILTER_NAMED(filter, name, ...)
#define ROS_ERROR_STREAM_FILTER_NAMED(filter, name, args)
#else
#define ROS_ERROR(...) ROS_LOG(::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM(args) ROS_LOG_STREAM(::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_NAMED(name, ...) ROS_LOG(::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_NAMED(name, args) ROS_LOG_STREAM(::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_ERROR_COND(cond, ...) ROS_LOG_COND(cond, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_ERROR_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_ERROR_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_ERROR_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_ERROR_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_ERROR_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Error, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_ERROR_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_ERROR_STREAM_FILTER_NAMED(filter, name, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Error, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#endif
#if (ROSCONSOLE_MIN_SEVERITY > ROSCONSOLE_SEVERITY_FATAL)
#define ROS_FATAL(...)
#define ROS_FATAL_STREAM(args)
#define ROS_FATAL_NAMED(name, ...)
#define ROS_FATAL_STREAM_NAMED(name, args)
#define ROS_FATAL_COND(cond, ...)
#define ROS_FATAL_STREAM_COND(cond, args)
#define ROS_FATAL_COND_NAMED(cond, name, ...)
#define ROS_FATAL_STREAM_COND_NAMED(cond, name, args)
#define ROS_FATAL_ONCE(...)
#define ROS_FATAL_STREAM_ONCE(args)
#define ROS_FATAL_ONCE_NAMED(name, ...)
#define ROS_FATAL_STREAM_ONCE_NAMED(name, args)
#define ROS_FATAL_THROTTLE(rate, ...)
#define ROS_FATAL_STREAM_THROTTLE(rate, args)
#define ROS_FATAL_THROTTLE_NAMED(rate, name, ...)
#define ROS_FATAL_STREAM_THROTTLE_NAMED(rate, name, args)
#define ROS_FATAL_DELAYED_THROTTLE(rate, ...)
#define ROS_FATAL_STREAM_DELAYED_THROTTLE(rate, args)
#define ROS_FATAL_DELAYED_THROTTLE_NAMED(rate, name, ...)
#define ROS_FATAL_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args)
#define ROS_FATAL_FILTER(filter, ...)
#define ROS_FATAL_STREAM_FILTER(filter, args)
#define ROS_FATAL_FILTER_NAMED(filter, name, ...)
#define ROS_FATAL_STREAM_FILTER_NAMED(filter, name, args)
#else
#define ROS_FATAL(...) ROS_LOG(::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM(args) ROS_LOG_STREAM(::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_NAMED(name, ...) ROS_LOG(::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_NAMED(name, args) ROS_LOG_STREAM(::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_FATAL_COND(cond, ...) ROS_LOG_COND(cond, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM_COND(cond, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_COND_NAMED(cond, name, ...) ROS_LOG_COND(cond, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_COND_NAMED(cond, name, args) ROS_LOG_STREAM_COND(cond, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_FATAL_ONCE(...) ROS_LOG_ONCE(::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM_ONCE(args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_ONCE_NAMED(name, ...) ROS_LOG_ONCE(::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_ONCE_NAMED(name, args) ROS_LOG_STREAM_ONCE(::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_FATAL_THROTTLE(rate, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM_THROTTLE(rate, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_THROTTLE_NAMED(rate, name, ...) ROS_LOG_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_FATAL_DELAYED_THROTTLE(rate, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM_DELAYED_THROTTLE(rate, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_DELAYED_THROTTLE_NAMED(rate, name, ...) ROS_LOG_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_DELAYED_THROTTLE_NAMED(rate, name, args) ROS_LOG_STREAM_DELAYED_THROTTLE(rate, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#define ROS_FATAL_FILTER(filter, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, __VA_ARGS__)
#define ROS_FATAL_STREAM_FILTER(filter, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Fatal, ROSCONSOLE_DEFAULT_NAME, args)
#define ROS_FATAL_FILTER_NAMED(filter, name, ...) ROS_LOG_FILTER(filter, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, __VA_ARGS__)
#define ROS_FATAL_STREAM_FILTER_NAMED(filter, name, args) ROS_LOG_STREAM_FILTER(filter, ::ros::console::levels::Fatal, std::string(ROSCONSOLE_NAME_PREFIX) + "." + name, args)
#endif