discard_stale_not_published_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2019, Magazino GmbH.
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 Magazino GmbH 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 # \author Guglielmo Gemignani
00036 
00037 # \brief Tests that expected items from GenericAnalyzer will be removed after the timeout if discard_stale is set to true
00038 
00039 import rospy, rostest, unittest
00040 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00041 from time import sleep
00042 import sys
00043 import threading
00044 
00045 
00046 class TestDiscardStale(unittest.TestCase):
00047     def __init__(self, *args):
00048         super(TestDiscardStale, self).__init__(*args)
00049 
00050         self._mutex = threading.Lock()
00051 
00052         self._agg_expecteds = []
00053         self._expecteds = {}
00054 
00055         rospy.init_node('test_expected_stale')
00056         self._diag_agg_sub = rospy.Subscriber("/diagnostics_agg",
00057                                               DiagnosticArray,
00058                                               self.diag_agg_cb)
00059         self._diag_sub = rospy.Subscriber("/diagnostics",
00060                                           DiagnosticArray,
00061                                           self.diag_cb)
00062         self._start_time = rospy.get_time()
00063 
00064     def diag_cb(self, msg):
00065         with self._mutex:
00066             for stat in msg.status:
00067                 self._expecteds[stat.name] = stat
00068 
00069     def diag_agg_cb(self, msg):
00070         with self._mutex:
00071             self._agg_expecteds = []
00072             for stat in msg.status:
00073                 self._agg_expecteds.append(stat)
00074 
00075     def test_discard_stale(self):
00076         expecteds = {}
00077         timeout = 10
00078 
00079         # wait for expecteds to be published
00080         while (len(expecteds.keys()) != 1 and
00081                not rospy.is_shutdown() and
00082                (rospy.get_time() - self._start_time < timeout)):
00083             sleep(1.0)
00084             with self._mutex:
00085                 expecteds = self._expecteds
00086 
00087         self.assert_(len(expecteds.keys()) == 1, "The expected diagnostics are not of length 1."
00088                                                  "Received diagnostics: {}".format(expecteds))
00089         self.assert_(expecteds['nonexistent2'].level == DiagnosticStatus.WARN)
00090 
00091         duration = 8
00092         # waiting a bit more than 5 seconds for the messages to become stale
00093         while not rospy.is_shutdown():
00094             sleep(1.0)
00095             if rospy.get_time() - self._start_time > duration:
00096                 break
00097 
00098         with self._mutex:
00099             self.assert_(len(self._agg_expecteds) == 1,
00100                          "There should only be one expected aggregated item left, {} found instead!".
00101                          format(len(self._agg_expecteds)))
00102             self.assert_(self._agg_expecteds[0].name == "/Nonexistent2",
00103                          "The name of the first aggregated message should be '/Nonexistent2'!")
00104             self.assert_(self._agg_expecteds[0].level == DiagnosticStatus.STALE,
00105                          "The level of the first aggregated message should be stale!")
00106 
00107         duration = 15
00108         # waiting a bit more than 5 seconds for the timeout of the aggregator to kick in
00109         while not rospy.is_shutdown():
00110             sleep(1.0)
00111             if rospy.get_time() - self._start_time > duration:
00112                 break
00113 
00114         with self._mutex:
00115             self.assert_(len(self._agg_expecteds) == 0,
00116                          "There should't be any aggregated items left, {} found instead! {}".
00117                          format(len(self._agg_expecteds), self._agg_expecteds))
00118 
00119 
00120 if __name__ == '__main__':
00121     rostest.run('diagnostic_aggregator', sys.argv[0], TestDiscardStale, sys.argv)
00122 


diagnostic_aggregator
Author(s): Kevin Watts, Brice Rebsamen
autogenerated on Tue Mar 26 2019 03:09:36