38 NAME =
'test_base_odomw_gt' 42 roslib.load_manifest(PKG)
47 from geometry_msgs.msg
import Twist,Vector3
58 from test_base
import BaseTest, Q, E
66 while not rospy.is_shutdown()
and not self.
success and ( timeout_t
is None or time.time() < timeout_t ) :
69 self.pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
71 timeout_t = time.time() + TEST_DURATION
76 error.shortest_euler_distance(self.
p3d_e,self.
odom_e)
77 print " error " +
" x:" + str(self.
odom_x - self.
p3d_x) \
79 +
" e:" + str(error.x) +
"," + str(error.y) +
"," + str(error.z) \
80 +
" t_odom:" + str(self.odom_e.z) +
" t_p3d:" + str(self.p3d_e.z)
83 total_error = abs(self.
odom_x - self.
p3d_x) + abs(self.
odom_y - self.
p3d_y) + abs(error.x) + abs(error.y) + abs(error.z)
84 print "total error:" + str(total_error) +
" tol:" + str(TARGET_TOL)
85 if total_error < TARGET_TOL:
90 if __name__ ==
'__main__':
91 rostest.run(PKG, sys.argv[0], W_GT, sys.argv)