38 import roslib; roslib.load_manifest(
'fingertip_pressure')
46 from fingertip_pressure.msg
import PressureInfo
51 super(PressureInfoTest, self).
__init__(*args)
52 rospy.init_node(
'pressure_info_test')
56 sub = rospy.Subscriber(
'pressure/r_gripper_motor_info',
58 timeout_t = rospy.get_time() + 2
59 print 'waiting for message' 60 while self.
msg ==
None and timeout_t > rospy.get_time():
62 print 'done waiting for message' 64 self.assertNotEquals(self.
msg,
None)
72 msg.sensor[i].center[j].x = msg.sensor[i].center[j].x + 0.004
73 msg.sensor[i].center[j].y = msg.sensor[i].center[j].y + 0.015 * fact
77 self.assertEquals(len(self.msg.sensor), 2,
"Should have two PressureInfoElements")
78 self.assertEquals(len(self.msg.sensor[1].center), 22,
"Should have 22 centers.")
79 self.assertEquals(len(self.msg.sensor[1].halfside1), 22,
"Should have 22 halfside1")
80 self.assertEquals(len(self.msg.sensor[1].halfside2), 22,
"Should have 22 halfside2")
81 self.assertEquals(len(self.msg.sensor[1].force_per_unit), 22,
"Should have 22 pressure")
87 a = self.msg.sensor[j].halfside1[i]
88 b = self.msg.sensor[j].halfside2[i]
89 c = self.msg.sensor[j].center[i]
90 c.y = c.y - yori * .005
91 det = a.x * b.y * c.z + b.x * c.y * a.z + c.x * a.y * b.z\
92 -a.x * c.y * b.z - b.x * a.y * c.z - c.x * b.y * a.z
93 self.assertTrue(det > 0,
94 "Wrong orientation for sensor %i on tip %i, det=%e, %e %e %e %e %e %e %e %e %e"%(i, j, det, a.x, a.y, a.z, b.x, b.y, b.z, c.x, c.y, c.z))
100 a = self.msg.sensor[j].halfside1[i]
101 b = self.msg.sensor[j].halfside2[i]
102 c = self.msg.sensor[j].center[i]
103 msg =
"Bound box error sensor %i, tip %i, %e %e %e %e %e %e %e %e %e"%(i, j, a.x, a.y, a.z, b.x, b.y, b.z, c.x, c.y, c.z)
104 self.assertTrue(c.x - abs(a.x) > 0, msg)
105 self.assertTrue(c.x - abs(b.x) > 0, msg)
106 self.assertTrue(c.x + abs(a.x) <= 0.035, msg)
107 self.assertTrue(c.x + abs(b.x) <= 0.035, msg)
108 self.assertTrue(yori * c.y - abs(a.y) >= 0, msg)
109 self.assertTrue(yori * c.y - abs(b.y) >= 0, msg)
110 self.assertTrue(yori * c.y + abs(a.y) < 11, msg)
111 self.assertTrue(yori * c.y + abs(b.y) < 11, msg)
112 self.assertTrue(abs(c.z) + abs(a.z) <= 11.5, msg)
113 self.assertTrue(abs(c.z) + abs(b.z) <= 11.5, msg)
116 if __name__ ==
'__main__':
120 rostest.rosrun(
'fingertip_pressure',
'pressure_info_test', PressureInfoTest)
121 except KeyboardInterrupt, e:
def test_array_sizes(self)
def test_bounding_box(self)
def test_cross_products(self)
Tests the PressureInfo message produced by sensor_info.py.