libuav original

Dependents:   UAVCAN UAVCAN_Subscriber

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers logger.hpp Source File

logger.hpp

00001 /*
00002  * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com>
00003  */
00004 
00005 #ifndef UAVCAN_PROTOCOL_LOGGER_HPP_INCLUDED
00006 #define UAVCAN_PROTOCOL_LOGGER_HPP_INCLUDED
00007 
00008 #include <uavcan/time.hpp>
00009 #include <uavcan/build_config.hpp>
00010 #include <uavcan/protocol/debug/LogMessage.hpp>
00011 #include <uavcan/marshal/char_array_formatter.hpp>
00012 #include <uavcan/node/publisher.hpp>
00013 #include <cstdlib>
00014 
00015 #if !defined(UAVCAN_CPP_VERSION) || !defined(UAVCAN_CPP11)
00016 # error UAVCAN_CPP_VERSION
00017 #endif
00018 
00019 namespace uavcan
00020 {
00021 /**
00022  * External log sink interface.
00023  * External log sink allows the application to install a hook on the logger output.
00024  * This can be used for application-wide logging.
00025  * Please refer to the @ref Logger class docs.
00026  */
00027 class UAVCAN_EXPORT ILogSink
00028 {
00029 public:
00030     typedef typename StorageType<typename protocol::debug::LogLevel::FieldTypes::value>::Type LogLevel;
00031 
00032     virtual ~ILogSink() { }
00033 
00034     /**
00035      * Logger will not sink messages with a severity level lower than returned by this method.
00036      * Default level is DEBUG.
00037      */
00038     virtual LogLevel getLogLevel() const { return protocol::debug::LogLevel::DEBUG; }
00039 
00040     /**
00041      * Logger will call this method for every log message which severity level
00042      * is not less than the current level of this sink.
00043      */
00044     virtual void log(const protocol::debug::LogMessage& message) = 0;
00045 };
00046 
00047 /**
00048  * Node logging convenience class.
00049  *
00050  * This class is based on the standard UAVCAN message type for logging - uavcan.protocol.debug.LogMessage.
00051  *
00052  * Provides logging methods of different severity; implements two sinks for the log messages:
00053  *  - Broadcast via the UAVCAN bus;
00054  *  - Sink into the application via @ref ILogSink.
00055  *
00056  * For each sink an individual severity threshold filter can be configured.
00057  */
00058 class UAVCAN_EXPORT Logger
00059 {
00060 public:
00061     typedef ILogSink::LogLevel LogLevel;
00062 
00063     /**
00064      * This value is higher than any valid severity value.
00065      * Use it to completely suppress the output.
00066      */
00067     static LogLevel getLogLevelAboveAll() { return (1U << protocol::debug::LogLevel::FieldTypes::value::BitLen) - 1U; }
00068 
00069 private:
00070     enum { DefaultTxTimeoutMs = 2000 };
00071 
00072     Publisher<protocol::debug::LogMessage> logmsg_pub_;
00073     protocol::debug::LogMessage msg_buf_;
00074     LogLevel level_;
00075     ILogSink* external_sink_;
00076 
00077     LogLevel getExternalSinkLevel() const
00078     {
00079         return (external_sink_ == UAVCAN_NULLPTR) ? getLogLevelAboveAll() : external_sink_->getLogLevel();
00080     }
00081 
00082 public:
00083     explicit Logger(INode& node)
00084         : logmsg_pub_(node)
00085         , external_sink_(UAVCAN_NULLPTR)
00086     {
00087         level_ = protocol::debug::LogLevel::ERROR;
00088         setTxTimeout(MonotonicDuration::fromMSec(DefaultTxTimeoutMs));
00089         UAVCAN_ASSERT(getTxTimeout() == MonotonicDuration::fromMSec(DefaultTxTimeoutMs));
00090     }
00091 
00092     /**
00093      * Initializes the logger, does not perform any network activity.
00094      * Must be called once before use.
00095      * Returns negative error code.
00096      */
00097     int init(const TransferPriority priority = TransferPriority::Lowest)
00098     {
00099         const int res = logmsg_pub_.init(priority);
00100         if (res < 0)
00101         {
00102             return res;
00103         }
00104         return 0;
00105     }
00106 
00107     /**
00108      * Logs one message. Please consider using helper methods instead of this one.
00109      *
00110      * The message will be broadcasted via the UAVCAN bus if the severity level of the
00111      * message is >= severity level of the logger.
00112      *
00113      * The message will be reported into the external log sink if the external sink is
00114      * installed and the severity level of the message is >= severity level of the external sink.
00115      *
00116      * Returns negative error code.
00117      */
00118     int log(const protocol::debug::LogMessage& message)
00119     {
00120         int retval = 0;
00121         if (message.level.value >= getExternalSinkLevel())
00122         {
00123             external_sink_->log(message);
00124         }
00125         if (message.level.value >= level_)
00126         {
00127             retval = logmsg_pub_.broadcast(message);
00128         }
00129         return retval;
00130     }
00131 
00132     /**
00133      * Severity filter for UAVCAN broadcasting.
00134      * Log message will be broadcasted via the UAVCAN network only if its severity is >= getLevel().
00135      * This does not affect the external sink.
00136      * Default level is ERROR.
00137      */
00138     LogLevel getLevel() const { return level_; }
00139     void setLevel(LogLevel level) { level_ = level; }
00140 
00141     /**
00142      * External log sink allows the application to install a hook on the logger output.
00143      * This can be used for application-wide logging.
00144      * Null pointer means that there's no log sink (can be used to remove it).
00145      * By default there's no log sink.
00146      */
00147     ILogSink* getExternalSink() const { return external_sink_; }
00148     void setExternalSink(ILogSink* sink) { external_sink_ = sink; }
00149 
00150     /**
00151      * Log message broadcast transmission timeout.
00152      * The default value should be acceptable for any use case.
00153      */
00154     MonotonicDuration getTxTimeout() const { return logmsg_pub_.getTxTimeout(); }
00155     void setTxTimeout(MonotonicDuration val) { logmsg_pub_.setTxTimeout(val); }
00156 
00157     /**
00158      * Helper methods for various severity levels and with formatting support.
00159      * These methods build a formatted log message and pass it into the method @ref log().
00160      *
00161      * Format string usage is a bit unusual: use "%*" for any argument type, use "%%" to print a percent character.
00162      * No other formating options are supported. Insufficient/extra arguments are ignored.
00163      *
00164      * Example format string:
00165      *      "What do you get if you %* %* by %*? %*. Extra arguments: %* %* %%"
00166      * ...with the following arguments:
00167      *      "multiply", 6, 9.0F 4.2e1
00168      * ...will likely produce this (floating point representation is platform dependent):
00169      *      "What do you get if you multiply 6 by 9.000000? 42.000000. Extra arguments: %* %* %"
00170      *
00171      * Formatting is not supported in C++03 mode.
00172      * @{
00173      */
00174 #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11
00175 
00176     template <typename... Args>
00177     int log(LogLevel level, const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT;
00178 
00179     template <typename... Args>
00180     inline int logDebug(const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT
00181     {
00182         return log(protocol::debug::LogLevel::DEBUG, source, format, args...);
00183     }
00184 
00185     template <typename... Args>
00186     inline int logInfo(const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT
00187     {
00188         return log(protocol::debug::LogLevel::INFO, source, format, args...);
00189     }
00190 
00191     template <typename... Args>
00192     inline int logWarning(const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT
00193     {
00194         return log(protocol::debug::LogLevel::WARNING, source, format, args...);
00195     }
00196 
00197     template <typename... Args>
00198     inline int logError(const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT
00199     {
00200         return log(protocol::debug::LogLevel::ERROR, source, format, args...);
00201     }
00202 
00203 #else
00204 
00205     int log(LogLevel level, const char* source, const char* text) UAVCAN_NOEXCEPT
00206     {
00207     #if UAVCAN_EXCEPTIONS
00208         try
00209     #endif
00210         {
00211             if (level >= level_ || level >= getExternalSinkLevel())
00212             {
00213                 msg_buf_.level.value = level;
00214                 msg_buf_.source = source;
00215                 msg_buf_.text = text;
00216                 return log(msg_buf_);
00217             }
00218             return 0;
00219         }
00220     #if UAVCAN_EXCEPTIONS
00221         catch (...)
00222         {
00223             return -ErrFailure;
00224         }
00225     #endif
00226     }
00227 
00228     int logDebug(const char* source, const char* text) UAVCAN_NOEXCEPT
00229     {
00230         return log(protocol::debug::LogLevel::DEBUG, source, text);
00231     }
00232 
00233     int logInfo(const char* source, const char* text) UAVCAN_NOEXCEPT
00234     {
00235         return log(protocol::debug::LogLevel::INFO, source, text);
00236     }
00237 
00238     int logWarning(const char* source, const char* text) UAVCAN_NOEXCEPT
00239     {
00240         return log(protocol::debug::LogLevel::WARNING, source, text);
00241     }
00242 
00243     int logError(const char* source, const char* text) UAVCAN_NOEXCEPT
00244     {
00245         return log(protocol::debug::LogLevel::ERROR, source, text);
00246     }
00247 
00248 #endif
00249     /**
00250      * @}
00251      */
00252 };
00253 
00254 #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11
00255 
00256 template <typename... Args>
00257 int Logger::log(LogLevel level, const char* source, const char* format, Args... args) UAVCAN_NOEXCEPT
00258 {
00259 #if UAVCAN_EXCEPTIONS
00260     try
00261 #endif
00262     {
00263         if (level >= level_ || level >= getExternalSinkLevel())
00264         {
00265             msg_buf_.level.value = level;
00266             msg_buf_.source = source;
00267             msg_buf_.text.clear();
00268             CharArrayFormatter<typename protocol::debug::LogMessage::FieldTypes::text> formatter(msg_buf_.text);
00269             formatter.write(format, args...);
00270             return log(msg_buf_);
00271         }
00272         return 0;
00273     }
00274 #if UAVCAN_EXCEPTIONS
00275     catch (...)
00276     {
00277         return -ErrFailure;
00278     }
00279 #endif
00280 }
00281 
00282 #endif
00283 
00284 }
00285 
00286 #endif // UAVCAN_PROTOCOL_LOGGER_HPP_INCLUDED