utest.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include "ros/console.h"
31 
32 #include "log4cxx/appenderskeleton.h"
33 #include "log4cxx/spi/loggingevent.h"
34 #ifdef _MSC_VER
35  // Have to be able to encode wchar LogStrings on windows.
36  #include "log4cxx/helpers/transcoder.h"
37 #endif
38 
39 #include <vector>
40 #include <stdexcept>
41 
42 #include <gtest/gtest.h>
43 
44 #include <boost/shared_array.hpp>
45 
46 class TestAppender : public log4cxx::AppenderSkeleton
47 {
48 public:
49  struct Info
50  {
51  log4cxx::LevelPtr level_;
52  std::string message_;
53  std::string logger_name_;
54  };
55 
56  typedef std::vector<Info> V_Info;
57 
58  V_Info info_;
59 
60 protected:
61  virtual void append(const log4cxx::spi::LoggingEventPtr& event, log4cxx::helpers::Pool&)
62  {
63  Info info;
64  info.level_ = event->getLevel();
65 #ifdef _MSC_VER
66  LOG4CXX_ENCODE_CHAR(msgstr, event->getMessage()); // has to handle LogString with wchar types.
67  info.message_ = msgstr; // msgstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
68 
69  LOG4CXX_ENCODE_CHAR(loggerstr, event->getLoggerName()); // has to handle LogString with wchar types.
70  info.logger_name_ = loggerstr; // loggerstr gets instantiated inside the LOG4CXX_ENCODE_CHAR macro
71 #else
72  info.message_ = event->getMessage();
73  info.logger_name_ = event->getLoggerName();
74 #endif
75 
76  info_.push_back( info );
77  }
78 
79  virtual void close()
80  {
81  }
82  virtual bool requiresLayout() const
83  {
84  return false;
85  }
86 };
87 
88 class TestAppenderWithThrow : public log4cxx::AppenderSkeleton
89 {
90 protected:
91  virtual void append(const log4cxx::spi::LoggingEventPtr&, log4cxx::helpers::Pool&)
92  {
93  throw std::runtime_error("This should be caught");
94  }
95 
96  virtual void close()
97  {
98  }
99  virtual bool requiresLayout() const
100  {
101  return false;
102  }
103 };
104 
106 {
107  BasicFilter(bool enabled)
108  : enabled_(enabled)
109  {}
110 
111  inline virtual bool isEnabled() { return enabled_; };
112 
113  bool enabled_;
114 };
115 
116 BasicFilter g_filter(true);
117 
118 #define DEFINE_COND_TESTS(name, macro_base, level, log4cxx_level) \
119  TEST(RosConsole, name##Cond) \
120  { \
121  TestAppender* appender = new TestAppender; \
122  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
123  macro_base##_COND(true, "Testing %d %d %d", 1, 2, 3); \
124  macro_base##_COND(false, "Testing %d %d %d", 1, 2, 3); \
125  ASSERT_EQ((int)appender->info_.size(), 1); \
126  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
127  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
128  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
129  } \
130  TEST(RosConsole, name##NamedCond) \
131  { \
132  TestAppender* appender = new TestAppender; \
133  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
134  macro_base##_COND_NAMED(true, "test", "Testing %d %d %d", 1, 2, 3); \
135  macro_base##_COND_NAMED(false, "test", "Testing %d %d %d", 1, 2, 3); \
136  ASSERT_EQ((int)appender->info_.size(), 1); \
137  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
138  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
139  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
140  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
141  } \
142  TEST(RosConsole, name##StreamCond) \
143  { \
144  TestAppender* appender = new TestAppender; \
145  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
146  macro_base##_STREAM_COND(true, "Testing " << 1 << " " << 2 << " " << 3); \
147  macro_base##_STREAM_COND(false, "Testing " << 1 << " " << 2 << " " << 3); \
148  ASSERT_EQ((int)appender->info_.size(), 1); \
149  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
150  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
151  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
152  } \
153  TEST(RosConsole, name##StreamCondNamed) \
154  { \
155  TestAppender* appender = new TestAppender; \
156  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
157  macro_base##_STREAM_COND_NAMED(true, "test", "Testing " << 1 << " " << 2 << " " << 3); \
158  macro_base##_STREAM_COND_NAMED(false, "test", "Testing " << 1 << " " << 2 << " " << 3); \
159  ASSERT_EQ((int)appender->info_.size(), 1); \
160  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
161  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
162  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
163  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
164  }
165 
166 #define DEFINE_ONCE_TESTS(name, macro_base, level, log4cxx_level) \
167  TEST(RosConsole, name##Once) \
168  { \
169  TestAppender* appender = new TestAppender; \
170  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
171  macro_base##_ONCE("Testing %d %d %d", 1, 2, 3); \
172  ASSERT_EQ((int)appender->info_.size(), 1); \
173  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
174  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
175  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
176  } \
177  TEST(RosConsole, name##NamedOnce) \
178  { \
179  TestAppender* appender = new TestAppender; \
180  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
181  macro_base##_ONCE_NAMED("test", "Testing %d %d %d", 1, 2, 3); \
182  ASSERT_EQ((int)appender->info_.size(), 1); \
183  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
184  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
185  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
186  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
187  } \
188  TEST(RosConsole, name##StreamOnce) \
189  { \
190  TestAppender* appender = new TestAppender; \
191  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
192  macro_base##_STREAM_ONCE("Testing " << 1 << " " << 2 << " " << 3); \
193  ASSERT_EQ((int)appender->info_.size(), 1); \
194  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
195  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
196  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
197  } \
198  TEST(RosConsole, name##StreamOnceNamed) \
199  { \
200  TestAppender* appender = new TestAppender; \
201  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
202  macro_base##_STREAM_ONCE_NAMED("test", "Testing " << 1 << " " << 2 << " " << 3); \
203  ASSERT_EQ((int)appender->info_.size(), 1); \
204  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
205  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
206  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
207  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
208  }
209 
210 #define DEFINE_THROTTLE_TESTS(name, macro_base, level, log4cxx_level) \
211  TEST(RosConsole, name##Throttle) \
212  { \
213  TestAppender* appender = new TestAppender; \
214  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
215  macro_base##_THROTTLE(0.5, "Testing %d %d %d", 1, 2, 3); \
216  ASSERT_EQ((int)appender->info_.size(), 1); \
217  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
218  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
219  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
220  } \
221  TEST(RosConsole, name##NamedThrottle) \
222  { \
223  TestAppender* appender = new TestAppender; \
224  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
225  macro_base##_THROTTLE_NAMED(0.5, "test", "Testing %d %d %d", 1, 2, 3); \
226  ASSERT_EQ((int)appender->info_.size(), 1); \
227  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
228  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
229  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
230  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
231  } \
232  TEST(RosConsole, name##StreamThrottle) \
233  { \
234  TestAppender* appender = new TestAppender; \
235  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
236  macro_base##_STREAM_THROTTLE(0.5, "Testing " << 1 << " " << 2 << " " << 3); \
237  ASSERT_EQ((int)appender->info_.size(), 1); \
238  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
239  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
240  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
241  } \
242  TEST(RosConsole, name##StreamThrottleNamed) \
243  { \
244  TestAppender* appender = new TestAppender; \
245  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
246  macro_base##_STREAM_THROTTLE_NAMED(0.5, "test", "Testing " << 1 << " " << 2 << " " << 3); \
247  ASSERT_EQ((int)appender->info_.size(), 1); \
248  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
249  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
250  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
251  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
252  }
253 
254 #define DEFINE_FILTER_TESTS(name, macro_base, level, log4cxx_level) \
255  TEST(RosConsole, name##Filter) \
256  { \
257  TestAppender* appender = new TestAppender; \
258  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
259  macro_base##_FILTER(&g_filter, "Testing %d %d %d", 1, 2, 3); \
260  ASSERT_EQ((int)appender->info_.size(), 1); \
261  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
262  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
263  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
264  } \
265  TEST(RosConsole, name##NamedFilter) \
266  { \
267  TestAppender* appender = new TestAppender; \
268  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
269  macro_base##_FILTER_NAMED(&g_filter, "test", "Testing %d %d %d", 1, 2, 3); \
270  ASSERT_EQ((int)appender->info_.size(), 1); \
271  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
272  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
273  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
274  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
275  } \
276  TEST(RosConsole, name##StreamFilter) \
277  { \
278  TestAppender* appender = new TestAppender; \
279  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
280  macro_base##_STREAM_FILTER(&g_filter, "Testing " << 1 << " " << 2 << " " << 3); \
281  ASSERT_EQ((int)appender->info_.size(), 1); \
282  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
283  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
284  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
285  } \
286  TEST(RosConsole, name##StreamFilterNamed) \
287  { \
288  TestAppender* appender = new TestAppender; \
289  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
290  macro_base##_STREAM_FILTER_NAMED(&g_filter, "test", "Testing " << 1 << " " << 2 << " " << 3); \
291  ASSERT_EQ((int)appender->info_.size(), 1); \
292  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
293  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
294  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
295  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
296  }
297 
298 #define DEFINE_LEVEL_TESTS(name, macro_base, level, log4cxx_level) \
299  TEST(RosConsole, name) \
300  { \
301  TestAppender* appender = new TestAppender; \
302  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
303  macro_base("Testing %d %d %d", 1, 2, 3); \
304  ASSERT_EQ((int)appender->info_.size(), 1); \
305  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
306  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
307  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
308  } \
309  TEST(RosConsole, name##Named) \
310  { \
311  TestAppender* appender = new TestAppender; \
312  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
313  macro_base##_NAMED("test", "Testing %d %d %d", 1, 2, 3); \
314  ASSERT_EQ((int)appender->info_.size(), 1); \
315  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
316  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
317  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
318  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
319  } \
320  TEST(RosConsole, name##Stream) \
321  { \
322  TestAppender* appender = new TestAppender; \
323  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
324  macro_base##_STREAM("Testing " << 1 << " " << 2 << " " << 3); \
325  ASSERT_EQ((int)appender->info_.size(), 1); \
326  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
327  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
328  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
329  } \
330  TEST(RosConsole, name##StreamNamed) \
331  { \
332  TestAppender* appender = new TestAppender; \
333  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->addAppender( appender ); \
334  macro_base##_STREAM_NAMED("test", "Testing " << 1 << " " << 2 << " " << 3); \
335  ASSERT_EQ((int)appender->info_.size(), 1); \
336  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Testing 1 2 3"); \
337  EXPECT_EQ(appender->info_[0].level_, log4cxx_level); \
338  EXPECT_STREQ(appender->info_[0].logger_name_.c_str(), ROSCONSOLE_ROOT_LOGGER_NAME".rosconsole.test"); \
339  log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME)->removeAppender( appender ); \
340  } \
341  DEFINE_COND_TESTS(name, macro_base, level, log4cxx_level) \
342  DEFINE_ONCE_TESTS(name, macro_base, level, log4cxx_level) \
343  DEFINE_THROTTLE_TESTS(name, macro_base, level, log4cxx_level) \
344  DEFINE_FILTER_TESTS(name, macro_base, level, log4cxx_level)
345 
346 DEFINE_LEVEL_TESTS(debug, ROS_DEBUG, ros::console::levels::Debug, log4cxx::Level::getDebug())
347 DEFINE_LEVEL_TESTS(info, ROS_INFO, ros::console::levels::Info, log4cxx::Level::getInfo())
348 DEFINE_LEVEL_TESTS(warn, ROS_WARN, ros::console::levels::Warn, log4cxx::Level::getWarn())
349 DEFINE_LEVEL_TESTS(error, ROS_ERROR, ros::console::levels::Error, log4cxx::Level::getError())
350 DEFINE_LEVEL_TESTS(fatal, ROS_FATAL, ros::console::levels::Fatal, log4cxx::Level::getFatal())
351 
352 TEST(RosConsole, loggingLevels)
353 {
354  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
355 
356  TestAppender* appender = new TestAppender;
357  logger->addAppender( appender );
358 
359  int pre_count = 0;
360  int post_count = 0;
361 
362  {
363  logger->setLevel( log4cxx::Level::getInfo() );
364  pre_count = appender->info_.size();
365  ROS_DEBUG("test");
366  ROS_INFO("test");
367  ROS_WARN("test");
368  ROS_ERROR("test");
369  ROS_FATAL("test");
370  post_count = appender->info_.size();
371  EXPECT_EQ(post_count, pre_count + 4);
372 
373  logger->setLevel( log4cxx::Level::getWarn() );
374  pre_count = appender->info_.size();
375  ROS_DEBUG("test");
376  ROS_INFO("test");
377  ROS_WARN("test");
378  ROS_ERROR("test");
379  ROS_FATAL("test");
380  post_count = appender->info_.size();
381  EXPECT_EQ(post_count, pre_count + 3);
382 
383  logger->setLevel( log4cxx::Level::getError() );
384  pre_count = appender->info_.size();
385  ROS_DEBUG("test");
386  ROS_INFO("test");
387  ROS_WARN("test");
388  ROS_ERROR("test");
389  ROS_FATAL("test");
390  post_count = appender->info_.size();
391  EXPECT_EQ(post_count, pre_count + 2);
392 
393  logger->setLevel( log4cxx::Level::getFatal() );
394  pre_count = appender->info_.size();
395  ROS_DEBUG("test");
396  ROS_INFO("test");
397  ROS_WARN("test");
398  ROS_ERROR("test");
399  ROS_FATAL("test");
400  post_count = appender->info_.size();
401  EXPECT_EQ(post_count, pre_count + 1);
402 
403  logger->setLevel( log4cxx::Level::getOff() );
404  pre_count = appender->info_.size();
405  ROS_DEBUG("test");
406  ROS_INFO("test");
407  ROS_WARN("test");
408  ROS_ERROR("test");
409  ROS_FATAL("test");
410  post_count = appender->info_.size();
411  EXPECT_EQ(post_count, pre_count);
412  }
413 
414  {
415  logger->setLevel( log4cxx::Level::getInfo() );
416  pre_count = appender->info_.size();
417  ROS_DEBUG_STREAM("test");
418  ROS_INFO_STREAM("test");
419  ROS_WARN_STREAM("test");
420  ROS_ERROR_STREAM("test");
421  ROS_FATAL_STREAM("test");
422  post_count = appender->info_.size();
423  EXPECT_EQ(post_count, pre_count + 4);
424 
425  logger->setLevel( log4cxx::Level::getWarn() );
426  pre_count = appender->info_.size();
427  ROS_DEBUG_STREAM("test");
428  ROS_INFO_STREAM("test");
429  ROS_WARN_STREAM("test");
430  ROS_ERROR_STREAM("test");
431  ROS_FATAL_STREAM("test");
432  post_count = appender->info_.size();
433  EXPECT_EQ(post_count, pre_count + 3);
434 
435  logger->setLevel( log4cxx::Level::getError() );
436  pre_count = appender->info_.size();
437  ROS_DEBUG_STREAM("test");
438  ROS_INFO_STREAM("test");
439  ROS_WARN_STREAM("test");
440  ROS_ERROR_STREAM("test");
441  ROS_FATAL_STREAM("test");
442  post_count = appender->info_.size();
443  EXPECT_EQ(post_count, pre_count + 2);
444 
445  logger->setLevel( log4cxx::Level::getFatal() );
446  pre_count = appender->info_.size();
447  ROS_DEBUG_STREAM("test");
448  ROS_INFO_STREAM("test");
449  ROS_WARN_STREAM("test");
450  ROS_ERROR_STREAM("test");
451  ROS_FATAL_STREAM("test");
452  post_count = appender->info_.size();
453  EXPECT_EQ(post_count, pre_count + 1);
454 
455  logger->setLevel( log4cxx::Level::getOff() );
456  pre_count = appender->info_.size();
457  ROS_DEBUG_STREAM("test");
458  ROS_INFO_STREAM("test");
459  ROS_WARN_STREAM("test");
460  ROS_ERROR_STREAM("test");
461  ROS_FATAL_STREAM("test");
462  post_count = appender->info_.size();
463  EXPECT_EQ(post_count, pre_count);
464  }
465 
466  {
467  logger->setLevel( log4cxx::Level::getInfo() );
468  pre_count = appender->info_.size();
469  ROS_DEBUG_NAMED("test_name", "test");
470  ROS_INFO_NAMED("test_name", "test");
471  ROS_WARN_NAMED("test_name", "test");
472  ROS_ERROR_NAMED("test_name", "test");
473  ROS_FATAL_NAMED("test_name", "test");
474  post_count = appender->info_.size();
475  EXPECT_EQ(post_count, pre_count + 4);
476 
477  logger->setLevel( log4cxx::Level::getWarn() );
478  pre_count = appender->info_.size();
479  ROS_DEBUG_NAMED("test_name", "test");
480  ROS_INFO_NAMED("test_name", "test");
481  ROS_WARN_NAMED("test_name", "test");
482  ROS_ERROR_NAMED("test_name", "test");
483  ROS_FATAL_NAMED("test_name", "test");
484  post_count = appender->info_.size();
485  EXPECT_EQ(post_count, pre_count + 3);
486 
487  logger->setLevel( log4cxx::Level::getError() );
488  pre_count = appender->info_.size();
489  ROS_DEBUG_NAMED("test_name", "test");
490  ROS_INFO_NAMED("test_name", "test");
491  ROS_WARN_NAMED("test_name", "test");
492  ROS_ERROR_NAMED("test_name", "test");
493  ROS_FATAL_NAMED("test_name", "test");
494  post_count = appender->info_.size();
495  EXPECT_EQ(post_count, pre_count + 2);
496 
497  logger->setLevel( log4cxx::Level::getFatal() );
498  pre_count = appender->info_.size();
499  ROS_DEBUG_NAMED("test_name", "test");
500  ROS_INFO_NAMED("test_name", "test");
501  ROS_WARN_NAMED("test_name", "test");
502  ROS_ERROR_NAMED("test_name", "test");
503  ROS_FATAL_NAMED("test_name", "test");
504  post_count = appender->info_.size();
505  EXPECT_EQ(post_count, pre_count + 1);
506 
507  logger->setLevel( log4cxx::Level::getOff() );
508  pre_count = appender->info_.size();
509  ROS_DEBUG_NAMED("test_name", "test");
510  ROS_INFO_NAMED("test_name", "test");
511  ROS_WARN_NAMED("test_name", "test");
512  ROS_ERROR_NAMED("test_name", "test");
513  ROS_FATAL_NAMED("test_name", "test");
514  post_count = appender->info_.size();
515  EXPECT_EQ(post_count, pre_count);
516  }
517 
518  {
519  logger->setLevel( log4cxx::Level::getInfo() );
520  pre_count = appender->info_.size();
521  ROS_DEBUG_STREAM_NAMED("test_name", "test");
522  ROS_INFO_STREAM_NAMED("test_name", "test");
523  ROS_WARN_STREAM_NAMED("test_name", "test");
524  ROS_ERROR_STREAM_NAMED("test_name", "test");
525  ROS_FATAL_STREAM_NAMED("test_name", "test");
526  post_count = appender->info_.size();
527  EXPECT_EQ(post_count, pre_count + 4);
528 
529  logger->setLevel( log4cxx::Level::getWarn() );
530  pre_count = appender->info_.size();
531  ROS_DEBUG_STREAM_NAMED("test_name", "test");
532  ROS_INFO_STREAM_NAMED("test_name", "test");
533  ROS_WARN_STREAM_NAMED("test_name", "test");
534  ROS_ERROR_STREAM_NAMED("test_name", "test");
535  ROS_FATAL_STREAM_NAMED("test_name", "test");
536  post_count = appender->info_.size();
537  EXPECT_EQ(post_count, pre_count + 3);
538 
539  logger->setLevel( log4cxx::Level::getError() );
540  pre_count = appender->info_.size();
541  ROS_DEBUG_STREAM_NAMED("test_name", "test");
542  ROS_INFO_STREAM_NAMED("test_name", "test");
543  ROS_WARN_STREAM_NAMED("test_name", "test");
544  ROS_ERROR_STREAM_NAMED("test_name", "test");
545  ROS_FATAL_STREAM_NAMED("test_name", "test");
546  post_count = appender->info_.size();
547  EXPECT_EQ(post_count, pre_count + 2);
548 
549  logger->setLevel( log4cxx::Level::getFatal() );
550  pre_count = appender->info_.size();
551  ROS_DEBUG_STREAM_NAMED("test_name", "test");
552  ROS_INFO_STREAM_NAMED("test_name", "test");
553  ROS_WARN_STREAM_NAMED("test_name", "test");
554  ROS_ERROR_STREAM_NAMED("test_name", "test");
555  ROS_FATAL_STREAM_NAMED("test_name", "test");
556  post_count = appender->info_.size();
557  EXPECT_EQ(post_count, pre_count + 1);
558 
559  logger->setLevel( log4cxx::Level::getOff() );
560  pre_count = appender->info_.size();
561  ROS_DEBUG_STREAM_NAMED("test_name", "test");
562  ROS_INFO_STREAM_NAMED("test_name", "test");
563  ROS_WARN_STREAM_NAMED("test_name", "test");
564  ROS_ERROR_STREAM_NAMED("test_name", "test");
565  ROS_FATAL_STREAM_NAMED("test_name", "test");
566  post_count = appender->info_.size();
567  EXPECT_EQ(post_count, pre_count);
568  }
569 
570  logger->removeAppender( appender );
571 }
572 
573 TEST(RosConsole, changingLevel)
574 {
575  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
576 
577  TestAppender* appender = new TestAppender;
578  logger->addAppender( appender );
579 
580  logger->setLevel( log4cxx::Level::getError() );
582  {
584  }
585 
586  EXPECT_EQ((int)appender->info_.size(), 2);
587 
588  logger->removeAppender( appender );
589 
590  logger->setLevel( log4cxx::Level::getDebug() );
591 }
592 
593 TEST(RosConsole, changingLoggerLevel)
594 {
595  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
596 
597  TestAppender* appender = new TestAppender;
598  logger->addAppender( appender );
599 
600  logger->setLevel(log4cxx::Level::getDebug());
603 
604  logger->setLevel(log4cxx::Level::getInfo());
607 
608  logger->setLevel(log4cxx::Level::getWarn());
611 
612  logger->setLevel(log4cxx::Level::getError());
615 
616  logger->setLevel(log4cxx::Level::getFatal());
619 
620  EXPECT_EQ((int)appender->info_.size(), 5);
621 
622  logger->removeAppender( appender );
623 
624  logger->setLevel( log4cxx::Level::getDebug() );
625 }
626 
627 TEST(RosConsole, longPrintfStyleOutput)
628 {
629  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
630 
631  TestAppender* appender = new TestAppender;
632  logger->addAppender( appender );
633 
634  std::stringstream ss;
635  for (int i = 0; i < 100000; ++i )
636  {
637  ss << 'a';
638  }
639 
640  ROS_INFO("%s", ss.str().c_str());
641 
642  ASSERT_EQ((int)appender->info_.size(), 1);
643  EXPECT_STREQ(appender->info_[0].message_.c_str(), ss.str().c_str());
644 
645  logger->removeAppender( appender );
646 
647  logger->setLevel( log4cxx::Level::getDebug() );
648 }
649 
650 TEST(RosConsole, throwingAppender)
651 {
652  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
653 
655  logger->addAppender( appender );
656 
657  try
658  {
659  ROS_INFO("Hello there");
660  }
661  catch (std::exception& e)
662  {
663  FAIL();
664  }
665 
666  logger->removeAppender( appender );
667  logger->setLevel( log4cxx::Level::getDebug() );
668 }
669 
670 void onceFunc()
671 {
673 }
674 
675 TEST(RosConsole, once)
676 {
677  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
678 
679  TestAppender* appender = new TestAppender;
680  logger->addAppender(appender);
681 
682  onceFunc();
683  onceFunc();
684 
685  EXPECT_EQ(appender->info_.size(), 1ULL);
686 
687  logger->removeAppender(appender);
688 }
689 
691 {
693 }
694 
695 TEST(RosConsole, throttle)
696 {
697  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
698 
699  TestAppender* appender = new TestAppender;
700  logger->addAppender(appender);
701 
702  ros::Time start = ros::Time::now();
703  while (ros::Time::now() <= start + ros::Duration(0.5))
704  {
705  throttleFunc();
706  ros::Duration(0.01).sleep();
707  }
708 
709  throttleFunc();
710 
711  EXPECT_EQ(appender->info_.size(), 2ULL);
712 
713  logger->removeAppender(appender);
714 }
715 
717 {
719 }
720 
722 {
724 }
725 
726 TEST(RosConsole, delayedThrottle)
727 {
728  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
729 
730  TestAppender* appender = new TestAppender;
731  logger->addAppender(appender);
732 
733  ros::Time start = ros::Time::now();
734  while (ros::Time::now() <= start + ros::Duration(0.4))
735  {
737  ros::Duration(0.01).sleep();
738  }
739 
740  EXPECT_EQ(appender->info_.size(), 0ULL);
741 
742  const int pre_count = appender->info_.size();
743  start = ros::Time::now();
744  while (ros::Time::now() <= start + ros::Duration(0.6))
745  {
747  ros::Duration(0.01).sleep();
748  }
749 
750  const int post_count = appender->info_.size();
751 
752  EXPECT_EQ(post_count, pre_count + 1);
753 
754  logger->removeAppender(appender);
755 }
756 
757 
759 {
761 }
762 
763 TEST(RosConsole, onceStream)
764 {
765  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
766 
767  TestAppender* appender = new TestAppender;
768  logger->addAppender(appender);
769 
770  onceStreamFunc();
771  onceStreamFunc();
772 
773  EXPECT_EQ(appender->info_.size(), 1ULL);
774 
775  logger->removeAppender(appender);
776 }
777 
779 {
781 }
782 
783 TEST(RosConsole, throttleStream)
784 {
785  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
786 
787  TestAppender* appender = new TestAppender;
788  logger->addAppender(appender);
789 
790  ros::Time start = ros::Time::now();
791  while (ros::Time::now() <= start + ros::Duration(0.5))
792  {
794  ros::Duration(0.01).sleep();
795  }
796 
798 
799  EXPECT_EQ(appender->info_.size(), 2ULL);
800 
801  logger->removeAppender(appender);
802 }
803 
805 {
807 }
808 
810 {
812 }
813 
814 TEST(RosConsole, delayedStreamThrottle)
815 {
816  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
817 
818  TestAppender* appender = new TestAppender;
819  logger->addAppender(appender);
820 
821  ros::Time start = ros::Time::now();
822  while (ros::Time::now() <= start + ros::Duration(0.4))
823  {
825  ros::Duration(0.01).sleep();
826  }
827 
828  EXPECT_EQ(appender->info_.size(), 0ULL);
829 
830  const int pre_count = appender->info_.size();
831  start = ros::Time::now();
832  while (ros::Time::now() <= start + ros::Duration(0.6))
833  {
835  ros::Duration(0.01).sleep();
836  }
837 
838  const int post_count = appender->info_.size();
839 
840  EXPECT_EQ(post_count, pre_count + 1);
841 
842  logger->removeAppender(appender);
843 }
844 
845 TEST(RosConsole, basicFilter)
846 {
847  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
848 
849  TestAppender* appender = new TestAppender;
850  logger->addAppender(appender);
851 
852  BasicFilter trueFilter(true), falseFilter(false);
855 
856  ASSERT_EQ(appender->info_.size(), 1ULL);
857  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Hello");
858 
859  logger->removeAppender(appender);
860 }
861 
862 TEST(RosConsole, basicFilterStream)
863 {
864  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
865 
866  TestAppender* appender = new TestAppender;
867  logger->addAppender(appender);
868 
869  BasicFilter trueFilter(true), falseFilter(false);
872 
873  ASSERT_EQ(appender->info_.size(), 1ULL);
874  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Hello");
875 
876  logger->removeAppender(appender);
877 }
878 
880 {
881  AdvancedFilter(bool enabled)
882  : enabled_(enabled)
883  , count_(0)
884  {}
885 
887  inline virtual bool isEnabled(ros::console::FilterParams& params)
888  {
889  fprintf(stderr, "%s %s:%d:%s\n", params.message, params.file, params.line, params.function);
890  ++count_;
891  return enabled_;
892  }
893 
894  bool enabled_;
895  int count_;
896 };
897 
898 TEST(RosConsole, advancedFilter)
899 {
900  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
901 
902  TestAppender* appender = new TestAppender;
903  logger->addAppender(appender);
904 
905  AdvancedFilter trueFilter(true), falseFilter(false);
908 
909  ASSERT_EQ(appender->info_.size(), 1ULL);
910  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Hello");
911  EXPECT_EQ(trueFilter.count_, 1);
912  EXPECT_EQ(falseFilter.count_, 1);
913 
914  logger->removeAppender(appender);
915 }
916 
917 TEST(RosConsole, advancedFilterStream)
918 {
919  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
920 
921  TestAppender* appender = new TestAppender;
922  logger->addAppender(appender);
923 
924  AdvancedFilter trueFilter(true), falseFilter(false);
927 
928  ASSERT_EQ(appender->info_.size(), 1ULL);
929  EXPECT_STREQ(appender->info_[0].message_.c_str(), "Hello");
930  EXPECT_EQ(trueFilter.count_, 1);
931  EXPECT_EQ(falseFilter.count_, 1);
932 
933  logger->removeAppender(appender);
934 }
935 
937 {
939  inline virtual bool isEnabled(ros::console::FilterParams& params)
940  {
941  params.out_message = "haha";
943  return true;
944  }
945 };
946 
947 TEST(RosConsole, changeFilter)
948 {
949  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
950 
951  TestAppender* appender = new TestAppender;
952  logger->addAppender(appender);
953 
954  ChangeFilter filter;
956 
957  ASSERT_EQ(appender->info_.size(), 1ULL);
958  EXPECT_STREQ(appender->info_[0].message_.c_str(), "haha");
959  EXPECT_EQ(appender->info_[0].level_, log4cxx::Level::getError());
960 
961  logger->removeAppender(appender);
962 }
963 
964 TEST(RosConsole, changeFilterStream)
965 {
966  log4cxx::LoggerPtr logger = log4cxx::Logger::getLogger(ROSCONSOLE_DEFAULT_NAME);
967 
968  TestAppender* appender = new TestAppender;
969  logger->addAppender(appender);
970 
971  ChangeFilter filter;
973 
974  ASSERT_EQ(appender->info_.size(), 1ULL);
975  EXPECT_STREQ(appender->info_[0].message_.c_str(), "haha");
976  EXPECT_EQ(appender->info_[0].level_, log4cxx::Level::getError());
977 
978  logger->removeAppender(appender);
979 }
980 
981 TEST(RosConsole, formatToBufferInitialZero)
982 {
984  size_t size = 0;
985  ros::console::formatToBuffer(buffer, size, "Hello World %d", 5);
986  EXPECT_EQ(size, 14U);
987  EXPECT_STREQ(buffer.get(), "Hello World 5");
988 }
989 
990 TEST(RosConsole, formatToBufferInitialLargerThanFormat)
991 {
992  boost::shared_array<char> buffer(new char[30]);
993  size_t size = 30;
994  ros::console::formatToBuffer(buffer, size, "Hello World %d", 5);
995  EXPECT_EQ(size, 30U);
996  EXPECT_STREQ(buffer.get(), "Hello World 5");
997 }
998 
999 TEST(RosConsole, formatToString)
1000 {
1001  std::string str = ros::console::formatToString("Hello World %d", 5);
1002  EXPECT_STREQ(str.c_str(), "Hello World 5");
1003 }
1004 
1005 int main(int argc, char **argv)
1006 {
1007  testing::InitGoogleTest(&argc, argv);
1008  ros::Time::init();
1009 
1011  log4cxx::Logger::getLogger(ROSCONSOLE_ROOT_LOGGER_NAME)->removeAllAppenders();
1012  log4cxx::Logger::getRootLogger()->setLevel(log4cxx::Level::getDebug());
1013  log4cxx::Logger::getLogger(ROSCONSOLE_ROOT_LOGGER_NAME)->setLevel(log4cxx::Level::getDebug());
1014 
1015  return RUN_ALL_TESTS();
1016 }
virtual bool requiresLayout() const
Definition: utest.cpp:82
#define ROS_LOG_THROTTLE(period, level, name,...)
Log to a given named logger at a given verbosity level, limited to a specific rate of printing...
Definition: console.h:454
#define ROS_FATAL(...)
virtual bool isEnabled()
Returns whether or not the log statement should be printed. Called before the log arguments are evalu...
Definition: console.h:236
#define ROS_INFO_NAMED(name,...)
AdvancedFilter(bool enabled)
Definition: utest.cpp:881
virtual void close()
Definition: utest.cpp:79
#define ROS_DEBUG_STREAM_NAMED(name, args)
ROSCONSOLE_DECL void notifyLoggerLevelsChanged()
Tells the system that a logger&#39;s level has changed.
Definition: rosconsole.cpp:665
Base-class for filters. Filters allow full user-defined control over whether or not a message should ...
Definition: console.h:228
#define DEFINE_LEVEL_TESTS(name, macro_base, level, log4cxx_level)
Definition: utest.cpp:298
#define ROS_ERROR_STREAM_NAMED(name, args)
Parameter structure passed to FilterBase::isEnabled(...);. Includes both input and output parameters...
Definition: console.h:191
#define ROS_WARN_NAMED(name,...)
virtual void close()
Definition: utest.cpp:96
#define ROS_LOG_STREAM_THROTTLE(period, level, name, args)
Log to a given named logger at a given verbosity level, limited to a specific rate of printing...
Definition: console.h:475
const char * message
[input] The formatted message that will be output
Definition: console.h:197
#define ROS_INFO_STREAM_NAMED(name, args)
#define ROSCONSOLE_AUTOINIT
Initializes the rosconsole library. Usually unnecessary to call directly.
Definition: console.h:324
virtual void append(const log4cxx::spi::LoggingEventPtr &, log4cxx::helpers::Pool &)
Definition: utest.cpp:91
#define ROS_WARN(...)
ROSCONSOLE_DECL std::string formatToString(const char *fmt,...)
Definition: rosconsole.cpp:474
#define ROSCONSOLE_ROOT_LOGGER_NAME
Definition: console.h:299
std::string out_message
[output] If set, writes this message instead of the original
Definition: console.h:204
Level level
[input/output] Severity level. If changed, uses the new level
Definition: console.h:201
BasicFilter(bool enabled)
Definition: utest.cpp:107
std::string logger_name_
Definition: thread_test.cpp:52
#define ROS_LOG_STREAM_ONCE(level, name, args)
Log to a given named logger at a given verbosity level, only the first time it is hit when enabled...
Definition: console.h:435
#define ROS_DEBUG_NAMED(name,...)
#define ROS_FATAL_STREAM(args)
#define ROS_FATAL_STREAM_NAMED(name, args)
void delayedThrottleStreamFunc2()
Definition: utest.cpp:809
#define ROS_INFO(...)
const char * file
[input] File the message came from
Definition: console.h:194
log4cxx::LevelPtr level_
Definition: thread_test.cpp:50
std::vector< Info > V_Info
Definition: utest.cpp:56
static void init()
int main(int argc, char **argv)
Definition: utest.cpp:1005
const char * function
[input] Function the message came from
Definition: console.h:196
void delayedThrottleFunc2()
Definition: utest.cpp:721
void throttleFunc()
Definition: utest.cpp:690
#define ROS_LOG_DELAYED_THROTTLE(period, level, name,...)
Log to a given named logger at a given verbosity level, limited to a specific rate of printing...
Definition: console.h:496
void throttleStreamFunc()
Definition: utest.cpp:778
#define ROS_WARN_STREAM(args)
BasicFilter g_filter(true)
#define ROS_DEBUG_STREAM(args)
void delayedThrottleFunc()
Definition: utest.cpp:716
virtual void append(const log4cxx::spi::LoggingEventPtr &event, log4cxx::helpers::Pool &)
Definition: utest.cpp:61
virtual bool isEnabled(ros::console::FilterParams &params)
Returns whether or not the log statement should be printed. Called once the message has been formatte...
Definition: utest.cpp:939
virtual bool isEnabled()
Returns whether or not the log statement should be printed. Called before the log arguments are evalu...
Definition: utest.cpp:111
#define ROS_LOG(level, name,...)
Log to a given named logger at a given verbosity level, with printf-style formatting.
Definition: console.h:572
void onceStreamFunc()
Definition: utest.cpp:758
#define ROS_INFO_STREAM(args)
void onceFunc()
Definition: utest.cpp:670
bool enabled_
Definition: utest.cpp:894
void delayedThrottleStreamFunc()
Definition: utest.cpp:804
#define ROS_LOG_FILTER(filter, level, name,...)
Log to a given named logger at a given verbosity level, with user-defined filtering, with printf-style formatting.
Definition: console.h:539
#define ROS_FATAL_NAMED(name,...)
int line
[input] Line the message came from
Definition: console.h:195
#define ROS_ERROR_NAMED(name,...)
static Time now()
#define ROS_LOG_STREAM_FILTER(filter, level, name, args)
Log to a given named logger at a given verbosity level, with user-defined filtering, with stream-style formatting.
Definition: console.h:556
#define ROS_LOG_STREAM_DELAYED_THROTTLE(period, level, name, args)
Log to a given named logger at a given verbosity level, limited to a specific rate of printing and po...
Definition: console.h:518
#define ROS_LOG_ONCE(level, name,...)
Log to a given named logger at a given verbosity level, only the first time it is hit when enabled...
Definition: console.h:416
bool sleep() const
#define ROS_ERROR_STREAM(args)
virtual bool requiresLayout() const
Definition: utest.cpp:99
TEST(RosConsole, loggingLevels)
Definition: utest.cpp:352
#define ROS_ERROR(...)
virtual bool isEnabled(ros::console::FilterParams &params)
Returns whether or not the log statement should be printed. Called once the message has been formatte...
Definition: utest.cpp:887
#define ROSCONSOLE_DEFAULT_NAME
Definition: console.h:301
std::string message_
Definition: thread_test.cpp:51
ROSCONSOLE_DECL void formatToBuffer(boost::shared_array< char > &buffer, size_t &buffer_size, const char *fmt,...)
Definition: rosconsole.cpp:464
#define ROS_WARN_STREAM_NAMED(name, args)
#define ROS_DEBUG(...)


rosconsole
Author(s): Josh Faust
autogenerated on Mon Feb 28 2022 23:30:41