test_cpu_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2017, TNO IVS, Helmond, Netherlands
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of the TNO IVS nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 # \author Rein Appeldoorn
36 
37 
38 import unittest
39 import rospy
40 import rostest
41 from diagnostic_msgs.msg import DiagnosticArray
42 
43 
44 class TestCPUMonitor(unittest.TestCase):
45 
46  def diagnostics_callback(self, msg):
47  self._msg = msg
48 
50  rospy.init_node('test_cpu_monitor')
51  self._expected_level = None
52  if rospy.has_param('~expected_level'):
53  self._expected_level = rospy.get_param('~expected_level')
54 
55  self._subscriber = rospy.Subscriber('diagnostics', DiagnosticArray, self.diagnostics_callback)
56  self._msg = None
57 
58  while not self._msg:
59  rospy.sleep(.1)
60  self._subscriber.unregister()
61 
62  self.assertEqual(len(self._msg.status), 1)
63  status = self._msg.status[0]
64 
65  for v in status.values:
66  percentage = float(v.value)
67  self.assertGreaterEqual(percentage, 0)
68  self.assertLessEqual(percentage, 100)
69 
70  if self._expected_level:
71  self.assertEqual(self._expected_level, status.level)
72 
73 
74 PKG = 'diagnostics_common_diagnostics'
75 NAME = 'test_cpu_monitor'
76 if __name__ == '__main__':
77  rostest.unitrun(PKG, NAME, TestCPUMonitor)


diagnostic_common_diagnostics
Author(s): Brice Rebsamen
autogenerated on Thu Oct 8 2020 03:19:37