45 roslib.load_manifest(PKG)
48 import os, os.path, threading, time
65 TARGET_PALM_TX = 0.118296477266
66 TARGET_PALM_TY = -0.113566972556
67 TARGET_PALM_TZ = 0.429595972393
68 TARGET_PALM_QX = -0.478307662414
69 TARGET_PALM_QY = 0.491088172771
70 TARGET_PALM_QZ = -0.547883729434
71 TARGET_PALM_QW = 0.479455530433
73 TARGET_FNGR_TX = 0.112382617544
74 TARGET_FNGR_TY = -0.190916084688
75 TARGET_FNGR_TZ = 0.378231687397
76 TARGET_FNGR_QX = -0.436046001411
77 TARGET_FNGR_QY = 0.528981109854
78 TARGET_FNGR_QZ = -0.506382999652
79 TARGET_FNGR_QW = 0.523086157085
93 print "pose ground truth received" 94 print "P3D pose translan: " +
"x: " + str(p3d.pose.pose.position.x)
95 print " " +
"y: " + str(p3d.pose.pose.position.y)
96 print " " +
"z: " + str(p3d.pose.pose.position.z)
97 print "P3D pose rotation: " +
"x: " + str(p3d.pose.pose.orientation.x)
98 print " " +
"y: " + str(p3d.pose.pose.orientation.y)
99 print " " +
"z: " + str(p3d.pose.pose.orientation.z)
100 print " " +
"w: " + str(p3d.pose.pose.orientation.w)
101 print "P3D rate translan: " +
"x: " + str(p3d.twist.twist.linear.x)
102 print " " +
"y: " + str(p3d.twist.twist.linear.y)
103 print " " +
"z: " + str(p3d.twist.twist.linear.z)
104 print "P3D rate rotation: " +
"x: " + str(p3d.twist.twist.angular.x)
105 print " " +
"y: " + str(p3d.twist.twist.angular.y)
106 print " " +
"z: " + str(p3d.twist.twist.angular.z)
110 pos_error = abs(p3d.pose.pose.position.x - TARGET_FNGR_TX) + \
111 abs(p3d.pose.pose.position.y - TARGET_FNGR_TY) + \
112 abs(p3d.pose.pose.position.z - TARGET_FNGR_TZ)
115 target_q = [TARGET_FNGR_QX \
121 p3d_q = [p3d.pose.pose.orientation.x \
122 ,p3d.pose.pose.orientation.y \
123 ,p3d.pose.pose.orientation.z \
124 ,p3d.pose.pose.orientation.w]
127 target_q_inv = quaternion_inverse(target_q)
128 rot_euler = euler_from_quaternion( quaternion_multiply(p3d_q, target_q_inv) )
129 rot_error = abs( rot_euler[0] ) + \
130 abs( rot_euler[1] ) + \
133 print " fngr Error pos: " + str(pos_error) +
" rot: " + str(rot_error)
140 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
148 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
149 print 'success finger' 155 pos_error = abs(p3d.pose.pose.position.x - TARGET_PALM_TX) + \
156 abs(p3d.pose.pose.position.y - TARGET_PALM_TY) + \
157 abs(p3d.pose.pose.position.z - TARGET_PALM_TZ)
160 target_q = [TARGET_PALM_QX \
166 p3d_q = [p3d.pose.pose.orientation.x \
167 ,p3d.pose.pose.orientation.y \
168 ,p3d.pose.pose.orientation.z \
169 ,p3d.pose.pose.orientation.w]
172 target_q_inv = quaternion_inverse(target_q)
173 rot_euler = euler_from_quaternion( quaternion_multiply(p3d_q, target_q_inv) )
174 rot_error = abs( rot_euler[0] ) + \
175 abs( rot_euler[1] ) + \
178 print " palm Error pos: " + str(pos_error) +
" rot: " + str(rot_error)
185 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
193 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
200 pub_gripper = rospy.Publisher(
"/l_gripper_position_controller/command", Float64)
201 rospy.Subscriber(
"/l_gripper_palm_pose_ground_truth", Odometry, self.
palmP3dInput)
202 rospy.Subscriber(
"/l_gripper_l_finger_pose_ground_truth", Odometry, self.
fngrP3dInput)
203 rospy.init_node(NAME, anonymous=
True)
204 timeout_t = time.time() + TEST_TIMEOUT
207 pub_gripper.publish(Float64(GRP_CMD_POS))
211 rospy.logerr(
"finger and palm pose test failed, there could be a problem with the gazebo_ros_p3d controller, tuck position has changed, or the gripper controller failed to open the gripper to 3cm width.")
215 if __name__ ==
'__main__':
216 rostest.run(PKG, sys.argv[0], ArmTest, sys.argv)
def fngrP3dInput(self, p3d)
def palmP3dInput(self, p3d)