Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
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
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
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
00121 self._diag_pub.publish(_camera_diag(level = 2))
00122 sleep(1.0)
00123
00124
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
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
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
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)