diagnostic_updater_test.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2008, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <gtest/gtest.h>
00036 #include <diagnostic_updater/diagnostic_updater.h>
00037 #include <diagnostic_updater/update_functions.h>
00038 #include <diagnostic_updater/DiagnosticStatusWrapper.h>
00039 #include <unistd.h>
00040 
00041 using namespace diagnostic_updater;
00042 
00043 class TestClass 
00044 {
00045 public: 
00046   void unwrapped(diagnostic_msgs::DiagnosticStatus &s)
00047   {
00048   }
00049 
00050   void wrapped(DiagnosticStatusWrapper &s)
00051   {
00052   }
00053 };
00054                                    
00055 TEST(DiagnosticUpdater, testDiagnosticUpdater)
00056 {
00057   class classFunction : public DiagnosticTask
00058   {
00059   public:
00060     classFunction() : DiagnosticTask("classFunction")
00061     {}
00062 
00063     void run(DiagnosticStatusWrapper &s) 
00064     {
00065       s.summary(0, "Test is running");
00066       s.addf("Value", "%f", 5);
00067       s.add("String", "Toto");
00068       s.add("Floating", 5.55);
00069       s.add("Integer", 5);
00070       s.addf("Formatted %s %i", "Hello", 5);
00071       s.add("Bool", true);
00072     }
00073   };
00074   
00075   TestClass c;
00076   ros::NodeHandle nh;
00077   
00078   Updater updater;
00079   
00080   updater.add("wrapped", &c, &TestClass::wrapped);
00081   
00082   classFunction cf;
00083   updater.add(cf);
00084 }
00085 
00086 TEST(DiagnosticUpdater, testDiagnosticStatusWrapperKeyValuePairs)
00087 {
00088   DiagnosticStatusWrapper stat;
00089   
00090   const char *message = "dummy";
00091   int level = 1;
00092   stat.summary(level, message);
00093   EXPECT_STREQ(message, stat.message.c_str()) << "DiagnosticStatusWrapper::summary failed to set message";
00094   EXPECT_EQ(level, stat.level) << "DiagnosticStatusWrapper::summary failed to set level";
00095 
00096   stat.addf("toto", "%.1f", 5.0);
00097   stat.add("baba", 5);
00098   stat.addf("foo", "%05i", 27);
00099 
00100   stat.add("bool", true);
00101   stat.add("bool2", false);
00102   
00103   EXPECT_STREQ("5.0", stat.values[0].value.c_str()) << "Bad value, adding a value with addf";
00104   EXPECT_STREQ("5", stat.values[1].value.c_str()) << "Bad value, adding a string with add";
00105   EXPECT_STREQ("00027", stat.values[2].value.c_str()) << "Bad value, adding a string with addf";
00106   EXPECT_STREQ("toto", stat.values[0].key.c_str()) << "Bad label, adding a value with add";
00107   EXPECT_STREQ("baba", stat.values[1].key.c_str()) << "Bad label, adding a string with add";
00108   EXPECT_STREQ("foo", stat.values[2].key.c_str()) << "Bad label, adding a string with addf";
00109 
00110   EXPECT_STREQ("bool", stat.values[3].key.c_str()) << "Bad label, adding a true bool key with add";
00111   EXPECT_STREQ("True", stat.values[3].value.c_str()) << "Bad label, adding a true bool with add";
00112 
00113   EXPECT_STREQ("bool2", stat.values[4].key.c_str()) << "Bad label, adding a false bool key with add";
00114   EXPECT_STREQ("False", stat.values[4].value.c_str()) << "Bad label, adding a false bool with add";
00115 }
00116 
00117 TEST(DiagnosticUpdater, testDiagnosticStatusWrapperMergeSummary)
00118 {
00119   DiagnosticStatusWrapper stat;
00120 
00121   stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Old");
00122   stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::OK, "New");
00123   EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::OK, stat.level) << "Bad level, merging levels (OK,OK)";
00124   EXPECT_STREQ("Old", stat.message.c_str()) << "Bad summary, merging levels (OK,OK)";
00125 
00126   stat.summary(diagnostic_msgs::DiagnosticStatus::OK, "Old");
00127   stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "New");
00128   EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::WARN, stat.level) << "Bad level, merging levels (OK,WARN)";
00129   EXPECT_STREQ("New", stat.message.c_str()) << "Bad summary, merging levels (OK,WARN)";
00130 
00131   stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Old");
00132   stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::WARN, "New");
00133   EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::WARN, stat.level) << "Bad level, merging levels (WARN,WARN)";
00134   EXPECT_STREQ("Old; New", stat.message.c_str()) << "Bad summary, merging levels (WARN,WARN)";
00135 
00136   stat.summary(diagnostic_msgs::DiagnosticStatus::WARN, "Old");
00137   stat.mergeSummary(diagnostic_msgs::DiagnosticStatus::ERROR, "New");
00138   EXPECT_EQ(diagnostic_msgs::DiagnosticStatus::ERROR, stat.level) << "Bad level, merging levels (WARN,ERROR)";
00139   EXPECT_STREQ("Old; New", stat.message.c_str()) << "Bad summary, merging levels (WARN,ERROR)";
00140 }
00141 
00142 TEST(DiagnosticUpdater, testFrequencyStatus)
00143 {
00144   double minFreq = 10;
00145   double maxFreq = 20;
00146   
00147   FrequencyStatus fs(FrequencyStatusParam(&minFreq, &maxFreq, 0.5, 2));
00148   
00149   DiagnosticStatusWrapper stat[5];
00150   fs.tick();
00151   usleep(20000);
00152   fs.run(stat[0]); // Should be too fast, 20 ms for 1 tick, lower limit should be 33ms.
00153   usleep(50000);
00154   fs.tick();
00155   fs.run(stat[1]); // Should be good, 70 ms for 2 ticks, lower limit should be 66 ms.
00156   usleep(300000);
00157   fs.tick();
00158   fs.run(stat[2]); // Should be good, 350 ms for 2 ticks, upper limit should be 400 ms.
00159   usleep(150000);
00160   fs.tick();
00161   fs.run(stat[3]); // Should be too slow, 450 ms for 2 ticks, upper limit should be 400 ms.
00162   fs.clear();
00163   fs.run(stat[4]); // Should be good, just cleared it.
00164 
00165   EXPECT_EQ(1, stat[0].level) << "max frequency exceeded but not reported";
00166   EXPECT_EQ(0, stat[1].level) << "within max frequency but reported error";
00167   EXPECT_EQ(0, stat[2].level) << "within min frequency but reported error";
00168   EXPECT_EQ(1, stat[3].level) << "min frequency exceeded but not reported";
00169   EXPECT_EQ(2, stat[4].level) << "freshly cleared should fail";
00170   EXPECT_STREQ("", stat[0].name.c_str()) << "Name should not be set by FrequencyStatus";
00171   EXPECT_STREQ("Frequency Status", fs.getName().c_str()) << "Name should be \"Frequency Status\"";
00172 }
00173 
00174 TEST(DiagnosticUpdater, testTimeStampStatus)
00175 {
00176   TimeStampStatus ts(DefaultTimeStampStatusParam);
00177 
00178   DiagnosticStatusWrapper stat[5];
00179   ts.run(stat[0]);
00180   ts.tick(ros::Time::now().toSec() + 2);
00181   ts.run(stat[1]);
00182   ts.tick(ros::Time::now());
00183   ts.run(stat[2]);
00184   ts.tick(ros::Time::now().toSec() - 4);
00185   ts.run(stat[3]);
00186   ts.tick(ros::Time::now().toSec() - 6);
00187   ts.run(stat[4]);
00188  
00189   EXPECT_EQ(1, stat[0].level) << "no data should return a warning";
00190   EXPECT_EQ(2, stat[1].level) << "too far future not reported";
00191   EXPECT_EQ(0, stat[2].level) << "now not accepted";
00192   EXPECT_EQ(0, stat[3].level) << "4 seconds ago not accepted";
00193   EXPECT_EQ(2, stat[4].level) << "too far past not reported";
00194   EXPECT_STREQ("", stat[0].name.c_str()) << "Name should not be set by TimeStapmStatus";
00195   EXPECT_STREQ("Timestamp Status", ts.getName().c_str()) << "Name should be \"Timestamp Status\"";
00196 }
00197 
00198 int main(int argc, char **argv){
00199   ros::init(argc, argv, "test_node");
00200   testing::InitGoogleTest(&argc, argv);
00201   return RUN_ALL_TESTS();
00202 }


diagnostic_updater
Author(s): Kevin Watts, Brice Rebsamen , Jeremy Leibs, Blaise Gassend
autogenerated on Tue Mar 26 2019 03:09:44