monitor_listen_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2009, 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 ##\author Kevin Watts
00036 
00037 ##\brief Tests receipt of test monitor messages from life tests
00038 
00039 from __future__ import with_statement
00040 
00041 DURATION = 20
00042 
00043 PKG = 'pr2_hardware_test_monitor'
00044 import roslib; roslib.load_manifest(PKG)
00045 
00046 import unittest
00047 import rospy, rostest
00048 from time import sleep
00049 import sys
00050 from optparse import OptionParser
00051 
00052 from pr2_self_test_msgs.msg import TestStatus
00053 import threading
00054 
00055 class TestMonitorUnit(unittest.TestCase):
00056     def __init__(self, *args):
00057         super(TestMonitorUnit, self).__init__(*args)
00058 
00059         parser = OptionParser(usage="usage ./%prog [options]", 
00060                               prog="monitor_listen_test.py")
00061         # Option comes with rostest, will fail w/o this line
00062         parser.add_option('--gtest_output', action="store",
00063                           dest="gtest")
00064 
00065         self._mutex = threading.Lock()
00066         rospy.init_node('test_monitor_listener')
00067         self._ignore_time = 5
00068         self._start_time = rospy.get_time()
00069         self._ok = True
00070         self._message = None
00071         self._level = 0
00072 
00073         self._start = rospy.get_time()
00074 
00075         options, args = parser.parse_args(rospy.myargv())
00076 
00077         rospy.Subscriber('test_status', TestStatus, self.cb)
00078     
00079     def cb(self, msg):
00080         if rospy.get_time() - self._start_time < self._ignore_time:
00081             return
00082 
00083         with self._mutex:
00084             self._ok = self._ok and (msg.test_ok == 0)
00085             if self._ok or (not self._ok and msg.test_ok != 0):
00086                 self._message = msg.message
00087                 self._level = msg.test_ok
00088 
00089     def test_monitor(self):
00090         while not rospy.is_shutdown():
00091             sleep(1.0)
00092             if rospy.get_time() - self._start > DURATION:
00093                 break
00094 
00095         with self._mutex:
00096             self.assert_(not rospy.is_shutdown(), "Rospy shutdown")
00097             self.assert_(self._message is not None, "No data from test monitor")
00098             self.assert_(self._ok, "Test Monitor reports error. Level: %d, Message: %s" % (self._level, self._message))
00099 
00100 
00101 if __name__ == '__main__':
00102     print 'SYS ARGS:', sys.argv
00103     rostest.run(PKG, sys.argv[0], TestMonitorUnit, sys.argv)


pr2_hardware_test_monitor
Author(s): Kevin Watts
autogenerated on Sat Dec 28 2013 17:54:19