discard_stale_not_published_test.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2019, Magazino GmbH.
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 Magazino GmbH 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 # \author Guglielmo Gemignani
36 
37 # \brief Tests that expected items from GenericAnalyzer will be removed after the timeout if discard_stale is set to true
38 
39 import rospy, rostest, unittest
40 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
41 from time import sleep
42 import sys
43 import threading
44 
45 
46 class TestDiscardStale(unittest.TestCase):
47  def __init__(self, *args):
48  super(TestDiscardStale, self).__init__(*args)
49 
50  self._mutex = threading.Lock()
51 
52  self._agg_expecteds = []
53  self._expecteds = {}
54 
55  rospy.init_node('test_expected_stale')
56  self._diag_agg_sub = rospy.Subscriber("/diagnostics_agg",
57  DiagnosticArray,
58  self.diag_agg_cb)
59  self._diag_sub = rospy.Subscriber("/diagnostics",
60  DiagnosticArray,
61  self.diag_cb)
62  self._start_time = rospy.get_time()
63 
64  def diag_cb(self, msg):
65  with self._mutex:
66  for stat in msg.status:
67  self._expecteds[stat.name] = stat
68 
69  def diag_agg_cb(self, msg):
70  with self._mutex:
71  self._agg_expecteds = []
72  for stat in msg.status:
73  self._agg_expecteds.append(stat)
74 
75  def test_discard_stale(self):
76  expecteds = {}
77  timeout = 10
78 
79  # wait for expecteds to be published
80  while (len(expecteds.keys()) != 1 and
81  not rospy.is_shutdown() and
82  (rospy.get_time() - self._start_time < timeout)):
83  sleep(1.0)
84  with self._mutex:
85  expecteds = self._expecteds
86 
87  self.assert_(len(expecteds.keys()) == 1, "The expected diagnostics are not of length 1."
88  "Received diagnostics: {}".format(expecteds))
89  self.assert_(expecteds['nonexistent2'].level == DiagnosticStatus.WARN)
90 
91  duration = 8
92  # waiting a bit more than 5 seconds for the messages to become stale
93  while not rospy.is_shutdown():
94  sleep(1.0)
95  if rospy.get_time() - self._start_time > duration:
96  break
97 
98  with self._mutex:
99  self.assert_(len(self._agg_expecteds) == 1,
100  "There should only be one expected aggregated item left, {} found instead!".
101  format(len(self._agg_expecteds)))
102  self.assert_(self._agg_expecteds[0].name == "/Nonexistent2",
103  "The name of the first aggregated message should be '/Nonexistent2'!")
104  self.assert_(self._agg_expecteds[0].level == DiagnosticStatus.STALE,
105  "The level of the first aggregated message should be stale!")
106 
107  duration = 15
108  # waiting a bit more than 5 seconds for the timeout of the aggregator to kick in
109  while not rospy.is_shutdown():
110  sleep(1.0)
111  if rospy.get_time() - self._start_time > duration:
112  break
113 
114  with self._mutex:
115  self.assert_(len(self._agg_expecteds) == 0,
116  "There should't be any aggregated items left, {} found instead! {}".
117  format(len(self._agg_expecteds), self._agg_expecteds))
118 
119 
120 if __name__ == '__main__':
121  rostest.run('diagnostic_aggregator', sys.argv[0], TestDiscardStale, sys.argv)
122 


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Wed Mar 27 2019 03:00:18