diagnostic_updater_test.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #include <gtest/gtest.h>
39 #include <unistd.h>
40 
41 using namespace diagnostic_updater;
42 
43 class TestClass
44 {
45 public:
46  void unwrapped(diagnostic_msgs::DiagnosticStatus &s)
47  {
48  }
49 
51  {
52  }
53 };
54 
55 TEST(DiagnosticUpdater, testDiagnosticUpdater)
56 {
57  class classFunction : public DiagnosticTask
58  {
59  public:
60  classFunction() : DiagnosticTask("classFunction")
61  {}
62 
63  void run(DiagnosticStatusWrapper &s)
64  {
65  s.summary(0, "Test is running");
66  s.addf("Value", "%f", 5);
67  s.add("String", "Toto");
68  s.add("Floating", 5.55);
69  s.add("Integer", 5);
70  s.addf("Formatted %s %i", "Hello", 5);
71  s.add("Bool", true);
72  }
73  };
74 
75  TestClass c;
76  ros::NodeHandle nh;
77 
79 
80  updater.add("wrapped", &c, &TestClass::wrapped);
81 
82  classFunction cf;
83  updater.add(cf);
84 }
85 
86 TEST(DiagnosticUpdater, testDiagnosticStatusWrapperKeyValuePairs)
87 {
89 
90  const char *message = "dummy";
91  int level = 1;
92  stat.summary(level, message);
93  EXPECT_STREQ(message, stat.message.c_str()) << "DiagnosticStatusWrapper::summary failed to set message";
94  EXPECT_EQ(level, stat.level) << "DiagnosticStatusWrapper::summary failed to set level";
95 
96  stat.addf("toto", "%.1f", 5.0);
97  stat.add("baba", 5);
98  stat.addf("foo", "%05i", 27);
99 
100  stat.add("bool", true);
101  stat.add("bool2", false);
102 
103  EXPECT_STREQ("5.0", stat.values[0].value.c_str()) << "Bad value, adding a value with addf";
104  EXPECT_STREQ("5", stat.values[1].value.c_str()) << "Bad value, adding a string with add";
105  EXPECT_STREQ("00027", stat.values[2].value.c_str()) << "Bad value, adding a string with addf";
106  EXPECT_STREQ("toto", stat.values[0].key.c_str()) << "Bad label, adding a value with add";
107  EXPECT_STREQ("baba", stat.values[1].key.c_str()) << "Bad label, adding a string with add";
108  EXPECT_STREQ("foo", stat.values[2].key.c_str()) << "Bad label, adding a string with addf";
109 
110  EXPECT_STREQ("bool", stat.values[3].key.c_str()) << "Bad label, adding a true bool key with add";
111  EXPECT_STREQ("True", stat.values[3].value.c_str()) << "Bad label, adding a true bool with add";
112 
113  EXPECT_STREQ("bool2", stat.values[4].key.c_str()) << "Bad label, adding a false bool key with add";
114  EXPECT_STREQ("False", stat.values[4].value.c_str()) << "Bad label, adding a false bool with add";
115 }
116 
117 TEST(DiagnosticUpdater, testDiagnosticStatusWrapperMergeSummary)
118 {
120 
123  EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::OK, stat.level) << "Bad level, merging levels (OK,OK)";
124  EXPECT_STREQ("Old", stat.message.c_str()) << "Bad summary, merging levels (OK,OK)";
125 
128  EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::WARN, stat.level) << "Bad level, merging levels (OK,WARN)";
129  EXPECT_STREQ("New", stat.message.c_str()) << "Bad summary, merging levels (OK,WARN)";
130 
133  EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::WARN, stat.level) << "Bad level, merging levels (WARN,WARN)";
134  EXPECT_STREQ("Old; New", stat.message.c_str()) << "Bad summary, merging levels (WARN,WARN)";
135 
138  EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::ERROR, stat.level) << "Bad level, merging levels (WARN,ERROR)";
139  EXPECT_STREQ("Old; New", stat.message.c_str()) << "Bad summary, merging levels (WARN,ERROR)";
140 }
141 
142 TEST(DiagnosticUpdater, testFrequencyStatus)
143 {
144  double minFreq = 10;
145  double maxFreq = 20;
146 
147  FrequencyStatus fs(FrequencyStatusParam(&minFreq, &maxFreq, 0.5, 2));
148 
149  DiagnosticStatusWrapper stat[5];
150  fs.tick();
151  usleep(20000);
152  fs.run(stat[0]); // Should be too fast, 20 ms for 1 tick, lower limit should be 33ms.
153  usleep(50000);
154  fs.tick();
155  fs.run(stat[1]); // Should be good, 70 ms for 2 ticks, lower limit should be 66 ms.
156  usleep(300000);
157  fs.tick();
158  fs.run(stat[2]); // Should be good, 350 ms for 2 ticks, upper limit should be 400 ms.
159  usleep(150000);
160  fs.tick();
161  fs.run(stat[3]); // Should be too slow, 450 ms for 2 ticks, upper limit should be 400 ms.
162  fs.clear();
163  fs.run(stat[4]); // Should be good, just cleared it.
164 
165  EXPECT_EQ(1, stat[0].level) << "max frequency exceeded but not reported";
166  EXPECT_EQ(0, stat[1].level) << "within max frequency but reported error";
167  EXPECT_EQ(0, stat[2].level) << "within min frequency but reported error";
168  EXPECT_EQ(1, stat[3].level) << "min frequency exceeded but not reported";
169  EXPECT_EQ(2, stat[4].level) << "freshly cleared should fail";
170  EXPECT_STREQ("", stat[0].name.c_str()) << "Name should not be set by FrequencyStatus";
171  EXPECT_STREQ("Frequency Status", fs.getName().c_str()) << "Name should be \"Frequency Status\"";
172 }
173 
174 TEST(DiagnosticUpdater, testTimeStampStatus)
175 {
177 
178  DiagnosticStatusWrapper stat[5];
179  ts.run(stat[0]);
180  ts.tick(ros::Time::now().toSec() + 2);
181  ts.run(stat[1]);
182  ts.tick(ros::Time::now());
183  ts.run(stat[2]);
184  ts.tick(ros::Time::now().toSec() - 4);
185  ts.run(stat[3]);
186  ts.tick(ros::Time::now().toSec() - 6);
187  ts.run(stat[4]);
188 
189  EXPECT_EQ(1, stat[0].level) << "no data should return a warning";
190  EXPECT_EQ(2, stat[1].level) << "too far future not reported";
191  EXPECT_EQ(0, stat[2].level) << "now not accepted";
192  EXPECT_EQ(0, stat[3].level) << "4 seconds ago not accepted";
193  EXPECT_EQ(2, stat[4].level) << "too far past not reported";
194  EXPECT_STREQ("", stat[0].name.c_str()) << "Name should not be set by TimeStapmStatus";
195  EXPECT_STREQ("Timestamp Status", ts.getName().c_str()) << "Name should be \"Timestamp Status\"";
196 }
197 
198 int main(int argc, char **argv){
199  ros::init(argc, argv, "test_node");
200  testing::InitGoogleTest(&argc, argv);
201  return RUN_ALL_TESTS();
202 }
static TimeStampStatusParam DefaultTimeStampStatusParam
Default TimeStampStatusParam. This is like calling the constructor with no arguments.
void unwrapped(diagnostic_msgs::DiagnosticStatus &s)
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills out this Task&#39;s DiagnosticStatusWrapper.
virtual void run(diagnostic_updater::DiagnosticStatusWrapper &stat)
Fills out this Task&#39;s DiagnosticStatusWrapper.
void summary(unsigned char lvl, const std::string s)
Fills out the level and message fields of the DiagnosticStatus.
A structure that holds the constructor parameters for the FrequencyStatus class.
XmlRpcServer s
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void add(const std::string &name, TaskFunction f)
Add a DiagnosticTask embodied by a name and function to the DiagnosticTaskVector. ...
Author: Blaise Gassend.
int main(int argc, char **argv)
void addf(const std::string &key, const char *format,...)
Add a key-value pair using a format string.
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
A diagnostic task that monitors the frequency of an event.
void wrapped(DiagnosticStatusWrapper &s)
void tick()
Signals that an event has occurred.
Diagnostic task to monitor the interval between events.
void clear()
Resets the statistics.
void mergeSummary(unsigned char lvl, const std::string s)
Merges a level and message with the existing ones.
const std::string & getName()
Returns the name of the DiagnosticTask.
TEST(DiagnosticUpdater, testDiagnosticUpdater)
static Time now()
DiagnosticTask is an abstract base class for collecting diagnostic data.
void add(const std::string &key, const T &val)
Add a key-value pair.
void tick(double stamp)
Signals an event. Timestamp stored as a double.
Wrapper for the diagnostic_msgs::DiagnosticStatus message that makes it easier to update...


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Wed Mar 27 2019 03:02:22