camera_warn_test.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2010, 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 ##\brief Tests that test monitor latches error state
00037 
00038 """
00039 This tests that a single error code from the wge100 camera is detected by the camera_listener
00040 and reported as a warning.
00041 """
00042 
00043 from __future__ import with_statement
00044 
00045 PKG = 'pr2_hardware_test_monitor'
00046 import roslib; roslib.load_manifest(PKG)
00047 
00048 import unittest
00049 import rospy, rostest
00050 from time import sleep
00051 import sys
00052 
00053 from diagnostic_msgs.msg import DiagnosticArray, DiagnosticStatus
00054 from pr2_self_test_msgs.msg import TestStatus
00055 from std_msgs.msg import Bool
00056 import std_msgs.msg
00057 from std_srvs.srv import *
00058 import threading
00059 
00060 GRACE_TIME = 35 # 30 + 5 seconds for HW monitor to be ready
00061 IGNORE_TIME = 5
00062 
00063 def _camera_diag(level = 0):
00064     array = DiagnosticArray()
00065     stat = DiagnosticStatus()
00066     stat.name = 'wge100: Driver Status'
00067     stat.level = level
00068     stat.message = 'OK'
00069 
00070     array.header.stamp = rospy.get_rostime()
00071     array.status.append(stat)
00072     
00073     return array
00074 
00075 class TestCameraWarn(unittest.TestCase):
00076     def __init__(self, *args):
00077         super(TestCameraWarn, self).__init__(*args)
00078 
00079         self._mutex = threading.Lock()
00080         rospy.init_node('test_monitor_latch_test')
00081         self._ok = True
00082         self._level = 0
00083 
00084         self._start = rospy.get_time()
00085         self._last_msg = None
00086         self._max_lvl = -1
00087         #self._max_lvl = -1
00088 
00089         self._halted = False
00090 
00091         self._snapped = False
00092         self._snapshot_sub = rospy.Subscriber('snapshot_trigger', std_msgs.msg.Empty, self._snap_cb)
00093 
00094         self._diag_pub = rospy.Publisher('/diagnostics', DiagnosticArray)
00095 
00096         self._reset_test = rospy.ServiceProxy('reset_test', Empty)
00097 
00098         rospy.Subscriber('test_status', TestStatus, self._cb)
00099 
00100     def _snap_cb(self, msg):
00101         self._snapped = True
00102 
00103     def _cb(self, msg):
00104         with self._mutex:
00105             if not self._last_msg:
00106                 self._start = rospy.get_time()
00107 
00108             self._last_msg = msg
00109 
00110             if rospy.get_time() - self._start > IGNORE_TIME:
00111                 self._max_lvl = max(msg.test_ok, self._max_lvl)
00112 
00113     def test_cam_warn(self):
00114         while not rospy.is_shutdown():
00115             self._diag_pub.publish(_camera_diag())
00116             sleep(1.0)
00117             if rospy.get_time() - self._start > GRACE_TIME:
00118                 break
00119 
00120         # Publish single camera error 
00121         self._diag_pub.publish(_camera_diag(level = 2))
00122         sleep(1.0)
00123 
00124         # Publish cameras OK 5x
00125         for i in range(0, 5):
00126             self._diag_pub.publish(_camera_diag())
00127             sleep(1.0)
00128 
00129         with self._mutex:
00130             self.assert_(not rospy.is_shutdown(), "Rospy shutdown")
00131 
00132             self.assert_(self._last_msg is not None, "No data from test monitor")
00133             
00134             # Check that message level is error state
00135             self.assert_(self._last_msg.test_ok == TestStatus.RUNNING, "Test monitor reports that we're not running. Level: %d" % self._last_msg.test_ok)
00136 
00137             # Check that we went into warning state
00138             self.assert_(self._max_lvl == TestStatus.WARNING, "We didn't get warning message from the camera listener. Max level: %d" % self._max_lvl)
00139 
00140             # Check that snapshot trigger was called
00141             self.assert_(not self._snapped, "Snapshot trigger was called, but we didn't halt")
00142 
00143 if __name__ == '__main__':
00144     if len(sys.argv) > 1 and sys.argv[1] == '-v':
00145         suite = unittest.TestSuite()
00146         suite.addTest(TestCameraWarn('test_cam_warn'))
00147 
00148         unittest.TextTestRunner(verbosity=2).run(suite)
00149     else:
00150         rostest.run(PKG, sys.argv[0], TestCameraWarn, sys.argv)


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