diagnostic_updater_test.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 
4 """
5 @author Brice Rebsamen <brice [dot] rebsamen [gmail]>
6 """
7 
8 import roslib
9 roslib.load_manifest('diagnostic_updater')
10 import rospy
11 from diagnostic_updater import *
12 import unittest
13 import time
14 
16  def __init__(self):
17  DiagnosticTask.__init__(self, "classFunction")
18 
19  def run(self, stat):
20  stat.summary(0, "Test is running")
21  stat.add("Value", "%f" % 5)
22  stat.add("String", "Toto")
23  stat.add("Floating", 5.55)
24  stat.add("Integer", 5)
25  stat.add("Formatted", "%s %i", "Hello", 5)
26  stat.add("Bool", True)
27  return stat
28 
29 class TestClass:
30  def wrapped(stat):
31  return stat
32 
33 
34 class TestDiagnosticStatusWrapper(unittest.TestCase):
35 
37  updater = Updater()
38 
39  c = TestClass()
40  updater.add("wrapped", c.wrapped)
41 
42  cf = ClassFunction()
43  updater.add(cf)
44 
45 
48 
49  message = "dummy"
50  level = 1
51  stat.summary(level, message)
52  self.assertEqual(message, stat.message, "DiagnosticStatusWrapper::summary failed to set message")
53  self.assertEqual(level, stat.level, "DiagnosticStatusWrapper::summary failed to set level")
54 
55  stat.add("toto", "%.1f" % 5.0)
56  stat.add("baba", 5)
57  stat.add("foo", "%05i" % 27)
58  stat.add("bool", True)
59  stat.add("bool2", False)
60 
61  self.assertEqual("5.0", stat.values[0].value, "Bad value, adding a value with addf")
62  self.assertEqual("5", stat.values[1].value, "Bad value, adding a string with add")
63  self.assertEqual("00027", stat.values[2].value, "Bad value, adding a string with addf")
64  self.assertEqual("toto", stat.values[0].key, "Bad label, adding a value with add")
65  self.assertEqual("baba", stat.values[1].key, "Bad label, adding a string with add")
66  self.assertEqual("foo", stat.values[2].key, "Bad label, adding a string with addf")
67 
68  self.assertEqual("bool", stat.values[3].key, "Bad label, adding a true bool key with add")
69  self.assertEqual("True", stat.values[3].value, "Bad value, adding a true bool with add")
70 
71  self.assertEqual("bool2", stat.values[4].key, "Bad label, adding a false bool key with add")
72  self.assertEqual("False", stat.values[4].value, "Bad value, adding a false bool with add")
73 
74 
76  freq_bound = {'min': 10, 'max': 20}
77 
78  fs = FrequencyStatus(FrequencyStatusParam(freq_bound, 0.5, 2))
79 
80  stat = [DiagnosticStatusWrapper() for i in range(5)]
81  fs.tick()
82  time.sleep(.02)
83  stat[0] = fs.run(stat[0]) # Should be too fast, 20 ms for 1 tick, lower limit should be 33ms.
84  time.sleep(.05)
85  fs.tick()
86  stat[1] = fs.run(stat[1]) # Should be good, 70 ms for 2 ticks, lower limit should be 66 ms.
87  time.sleep(.3)
88  fs.tick()
89  stat[2] = fs.run(stat[2]) # Should be good, 350 ms for 2 ticks, upper limit should be 400 ms.
90  time.sleep(.15)
91  fs.tick()
92  stat[3] = fs.run(stat[3]) # Should be too slow, 450 ms for 2 ticks, upper limit should be 400 ms.
93  fs.clear()
94  stat[4] = fs.run(stat[4]) # Should be good, just cleared it.
95 
96  self.assertEqual(1, stat[0].level, "max frequency exceeded but not reported")
97  self.assertEqual(0, stat[1].level, "within max frequency but reported error")
98  self.assertEqual(0, stat[2].level, "within min frequency but reported error")
99  self.assertEqual(1, stat[3].level, "min frequency exceeded but not reported")
100  self.assertEqual(2, stat[4].level, "freshly cleared should fail")
101  self.assertEqual("", stat[0].name, "Name should not be set by FrequencyStatus")
102  self.assertEqual("Frequency Status", fs.getName(), "Name should be \"Frequency Status\"")
103 
104 
106  ts = TimeStampStatus()
107 
108  stat = [DiagnosticStatusWrapper() for i in range(5)]
109  stat[0] = ts.run(stat[0])
110  ts.tick(rospy.Time.now().to_sec() + 2)
111  stat[1] = ts.run(stat[1])
112  ts.tick(rospy.Time.now())
113  stat[2] = ts.run(stat[2])
114  ts.tick(rospy.Time.now().to_sec() - 4)
115  stat[3] = ts.run(stat[3])
116  ts.tick(rospy.Time.now().to_sec() - 6)
117  stat[4] = ts.run(stat[4])
118 
119  self.assertEqual(1, stat[0].level, "no data should return a warning")
120  self.assertEqual(2, stat[1].level, "too far future not reported")
121  self.assertEqual(0, stat[2].level, "now not accepted")
122  self.assertEqual(0, stat[3].level, "4 seconds ago not accepted")
123  self.assertEqual(2, stat[4].level, "too far past not reported")
124  self.assertEqual("", stat[0].name, "Name should not be set by TimeStapmStatus")
125  self.assertEqual("Timestamp Status", ts.getName(), "Name should be \"Timestamp Status\"")
126 
127 
128 if __name__ == '__main__':
129  rospy.init_node("test_node")
130  unittest.main()
A structure that holds the constructor parameters for the FrequencyStatus class.
Manages a list of diagnostic tasks, and calls them in a rate-limited manner.
A diagnostic task that monitors the frequency of an event.
Diagnostic task to monitor the interval between events.
DiagnosticTask is an abstract base class for collecting diagnostic data.
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 Thu Oct 8 2020 03:19:34