45 roslib.load_manifest(PKG)
48 import os, os.path, threading, time
74 super(PoseTest, self).
__init__(*args)
80 print "pose ground truth received" 81 print "P3D pose translan: " +
"x: " + str(p3d.pose.pose.position.x)
82 print " " +
"y: " + str(p3d.pos.position.y)
83 print " " +
"z: " + str(p3d.pose.pose.position.z)
84 print "P3D pose rotation: " +
"x: " + str(p3d.pose.pose.orientation.x)
85 print " " +
"y: " + str(p3d.pose.pose.orientation.y)
86 print " " +
"z: " + str(p3d.pose.pose.orientation.z)
87 print " " +
"w: " + str(p3d.pose.pose.orientation.w)
88 print "P3D rate translan: " +
"x: " + str(p3d.vel.vel.vx)
89 print " " +
"y: " + str(p3d.vel.vel.vy)
90 print " " +
"z: " + str(p3d.vel.vel.vz)
91 print "P3D rate rotation: " +
"x: " + str(p3d.vel.ang_vel.vx)
92 print " " +
"y: " + str(p3d.vel.ang_vel.vy)
93 print " " +
"z: " + str(p3d.vel.ang_vel.vz)
97 pos_error = abs(p3d.pose.pose.position.x - TARGET_BASE_TX) + \
98 abs(p3d.pose.pose.position.y - TARGET_BASE_TY) + \
99 abs(p3d.pose.pose.position.z - TARGET_BASE_TZ) * 0
102 target_q = [TARGET_BASE_QX \
108 p3d_q = [p3d.pose.pose.orientation.x \
109 ,p3d.pose.pose.orientation.y \
110 ,p3d.pose.pose.orientation.z \
111 ,p3d.pose.pose.orientation.w]
114 target_q_inv = quaternion_inverse(target_q)
115 rot_euler = euler_from_quaternion( quaternion_multiply(p3d_q, target_q_inv) )
116 rot_error = abs( rot_euler[0] ) + \
117 abs( rot_euler[1] ) + \
120 print " base Error pos: " + str(pos_error) +
" rot: " + str(rot_error)
127 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
135 if rot_error < ROT_TARGET_TOL
and pos_error < POS_TARGET_TOL:
142 rospy.Subscriber(
"/base_pose_ground_truth", Odometry, self.
baseP3dInput)
143 rospy.init_node(NAME, anonymous=
True)
144 timeout_t = time.time() + TEST_TIMEOUT
145 while not rospy.is_shutdown()
and not self.
base_success and time.time() < timeout_t:
148 if __name__ ==
'__main__':
149 rostest.run(PKG, sys.argv[0], PoseTest, sys.argv)
def baseP3dInput(self, p3d)