Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependents: UAVCAN UAVCAN_Subscriber
logger.cpp
00001 /* 00002 * Copyright (C) 2014 Pavel Kirienko <pavel.kirienko@gmail.com> 00003 */ 00004 00005 #include <gtest/gtest.h> 00006 #include <uavcan/protocol/logger.hpp> 00007 #include "helpers.hpp" 00008 00009 00010 struct LogSink : public uavcan::ILogSink 00011 { 00012 std::queue<uavcan::protocol::debug::LogMessage> msgs; 00013 LogLevel level; 00014 00015 LogSink() 00016 : level(uavcan::protocol::debug::LogLevel::ERROR) 00017 { } 00018 00019 LogLevel getLogLevel() const { return level; } 00020 00021 void log(const uavcan::protocol::debug::LogMessage& message) 00022 { 00023 msgs.push(message); 00024 std::cout << message << std::endl; 00025 } 00026 00027 uavcan::protocol::debug::LogMessage pop() 00028 { 00029 if (msgs.empty()) 00030 { 00031 std::cout << "LogSink is empty" << std::endl; 00032 std::abort(); 00033 } 00034 const uavcan::protocol::debug::LogMessage m = msgs.front(); 00035 msgs.pop(); 00036 return m; 00037 } 00038 00039 bool popMatchByLevelAndText(int level, const std::string& source, const std::string& text) 00040 { 00041 if (msgs.empty()) 00042 { 00043 std::cout << "LogSink is empty" << std::endl; 00044 return false; 00045 } 00046 const uavcan::protocol::debug::LogMessage m = pop(); 00047 return 00048 level == m.level.value && 00049 source == m.source && 00050 text == m.text; 00051 } 00052 }; 00053 00054 00055 TEST(Logger, Basic) 00056 { 00057 InterlinkedTestNodesWithSysClock nodes; 00058 00059 uavcan::Logger logger(nodes.a); 00060 00061 ASSERT_EQ(uavcan::protocol::debug::LogLevel::ERROR, logger.getLevel()); 00062 00063 LogSink sink; 00064 00065 // Will fail - types are not registered 00066 uavcan::GlobalDataTypeRegistry::instance().reset(); 00067 ASSERT_GT(0, logger.logError("foo", "Error (fail - type is not registered)")); 00068 ASSERT_EQ(0, logger.logDebug("foo", "Debug (ignored - low logging level)")); 00069 00070 ASSERT_FALSE(logger.getExternalSink()); 00071 logger.setExternalSink(&sink); 00072 ASSERT_EQ(&sink, logger.getExternalSink()); 00073 00074 uavcan::GlobalDataTypeRegistry::instance().reset(); 00075 uavcan::DefaultDataTypeRegistrator<uavcan::protocol::debug::LogMessage> _reg1; 00076 00077 SubscriberWithCollector<uavcan::protocol::debug::LogMessage> log_sub(nodes.b); 00078 ASSERT_LE(0, log_sub.start()); 00079 00080 // Sink test 00081 ASSERT_EQ(0, logger.logDebug("foo", "Debug (ignored due to low logging level)")); 00082 ASSERT_TRUE(sink.msgs.empty()); 00083 00084 sink.level = uavcan::protocol::debug::LogLevel::DEBUG; 00085 ASSERT_EQ(0, logger.logDebug("foo", "Debug (sink only)")); 00086 ASSERT_TRUE(sink.popMatchByLevelAndText(uavcan::protocol::debug::LogLevel::DEBUG, "foo", "Debug (sink only)")); 00087 00088 ASSERT_LE(0, logger.logError("foo", "Error")); 00089 nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(10)); 00090 ASSERT_TRUE(log_sub.collector.msg.get()); 00091 ASSERT_EQ(log_sub.collector.msg->level.value, uavcan::protocol::debug::LogLevel::ERROR); 00092 ASSERT_EQ(log_sub.collector.msg->source, "foo"); 00093 ASSERT_EQ(log_sub.collector.msg->text, "Error"); 00094 00095 logger.setLevel(uavcan::protocol::debug::LogLevel::DEBUG); 00096 ASSERT_LE(0, logger.logWarning("foo", "Warning")); 00097 nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(10)); 00098 ASSERT_EQ(log_sub.collector.msg->level.value, uavcan::protocol::debug::LogLevel::WARNING); 00099 ASSERT_EQ(log_sub.collector.msg->source, "foo"); 00100 ASSERT_EQ(log_sub.collector.msg->text, "Warning"); 00101 00102 ASSERT_LE(0, logger.logInfo("foo", "Info")); 00103 nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(10)); 00104 ASSERT_EQ(log_sub.collector.msg->level.value, uavcan::protocol::debug::LogLevel::INFO); 00105 ASSERT_EQ(log_sub.collector.msg->source, "foo"); 00106 ASSERT_EQ(log_sub.collector.msg->text, "Info"); 00107 00108 ASSERT_LE(0, logger.logDebug("foo", "Debug")); 00109 nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(10)); 00110 ASSERT_EQ(log_sub.collector.msg->level.value, uavcan::protocol::debug::LogLevel::DEBUG); 00111 ASSERT_EQ(log_sub.collector.msg->source, "foo"); 00112 ASSERT_EQ(log_sub.collector.msg->text, "Debug"); 00113 00114 ASSERT_TRUE(sink.popMatchByLevelAndText(uavcan::protocol::debug::LogLevel::ERROR, "foo", "Error")); 00115 ASSERT_TRUE(sink.popMatchByLevelAndText(uavcan::protocol::debug::LogLevel::WARNING, "foo", "Warning")); 00116 ASSERT_TRUE(sink.popMatchByLevelAndText(uavcan::protocol::debug::LogLevel::INFO, "foo", "Info")); 00117 ASSERT_TRUE(sink.popMatchByLevelAndText(uavcan::protocol::debug::LogLevel::DEBUG, "foo", "Debug")); 00118 } 00119 00120 #if !defined(UAVCAN_CPP_VERSION) || !defined(UAVCAN_CPP11) 00121 # error UAVCAN_CPP_VERSION 00122 #endif 00123 00124 #if UAVCAN_CPP_VERSION >= UAVCAN_CPP11 00125 00126 TEST(Logger, Cpp11Formatting) 00127 { 00128 InterlinkedTestNodesWithSysClock nodes; 00129 00130 uavcan::Logger logger(nodes.a); 00131 logger.setLevel(uavcan::protocol::debug::LogLevel::DEBUG); 00132 00133 SubscriberWithCollector<uavcan::protocol::debug::LogMessage> log_sub(nodes.b); 00134 ASSERT_LE(0, log_sub.start()); 00135 00136 ASSERT_LE(0, logger.logWarning("foo", "char='%*', %* is %*", '$', "double", 12.34)); 00137 nodes.spinBoth(uavcan::MonotonicDuration::fromMSec(10)); 00138 ASSERT_TRUE(log_sub.collector.msg.get()); 00139 ASSERT_EQ(log_sub.collector.msg->level.value, uavcan::protocol::debug::LogLevel::WARNING); 00140 ASSERT_EQ(log_sub.collector.msg->source, "foo"); 00141 ASSERT_EQ(log_sub.collector.msg->text, "char='$', double is 12.34"); 00142 } 00143 00144 #endif
Generated on Tue Jul 12 2022 17:17:33 by
