38 from __future__
import with_statement
39 PKG =
'pr2_mechanism_diagnostics' 40 import roslib; roslib.load_manifest(PKG)
42 import rospy, rostest, unittest
43 from diagnostic_msgs.msg
import DiagnosticArray, DiagnosticStatus
47 from time
import sleep
53 super(TestMechDiag, self).
__init__(*args)
62 self.
_cal = rospy.get_param(
"mech_diag/cal",
True)
63 self.
_nan = rospy.get_param(
"mech_diag/nan",
False)
65 self.
_running = rospy.get_param(
"mech_diag/running",
True)
66 self.
_overrun = rospy.get_param(
"mech_diag/overrun",
False)
68 sub_diag = rospy.Subscriber(
'/diagnostics', DiagnosticArray, self.
_diag_cb)
72 for stat
in msg.status:
73 if stat.name.startswith(
'Joint'):
75 if stat.name.startswith(
'Controller'):
77 if stat.name.find(
'No controllers') > 0:
83 while not rospy.is_shutdown()
and (rospy.get_time() - self.
_start_time) < WAIT_TIME:
86 self.assert_(
not rospy.is_shutdown(),
"Rospy shutdown")
89 if len(self._joints.items()) == 0:
90 self.assert_(
False,
"No joint data in diagnostics")
91 for key, val
in self._joints.iteritems():
93 self.assert_(val.level == 2,
"Joint %s was not ERROR, but was NaN. Level %d" % (val.name, val.level))
95 self.assert_(val.level == 0,
"Joint %s was not OK. Level %d" % (val.name, val.level))
97 self.assert_(val.level == 1,
"Joint %s was not warning, but was uncalibrated. Level %d" % (val.name, val.level))
99 if len(self._controllers.items()) == 0:
100 self.assert_(
False,
"No controller data in diagnostics")
102 for key, val
in self._controllers.iteritems():
104 self.assert_(val.level == 1,
"Controller %s was not WARN, but was overrun. Level %d" % (val.name, val.level))
106 self.assert_(val.level == 0,
"Controller %s was not OK. Level %d" % (val.name, val.level))
108 if __name__ ==
'__main__':
109 rospy.init_node(
'test_mech_diag_nominal')
111 rostest.run(PKG, sys.argv[0], TestMechDiag, sys.argv)
113 suite = unittest.TestSuite()
116 unittest.TextTestRunner(verbosity = 2).run(suite)