38 NAME =
'test_base_odomxy_gt' 42 roslib.load_manifest(PKG)
45 import os, os.path, threading, time
47 from geometry_msgs.msg
import Twist,Vector3
58 from test_base
import BaseTest, E, Q
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
80 if total_error/total_dist < TARGET_TOL:
84 rospy.logerr(
"Testing pr2 base odometry control against simulated ground truth with target (vx,vy) = (0.25,0.25), but odom data does not match gound truth from simulation. Total deviation in position is %f percent over a distance of %f meters."%(total_error/total_dist, total_dist));
86 rospy.loginfo(
"Testing pr2 base odometry control against simulated ground truth with target (vx,vy) = (0.25,0.25), total deviation in position is %f percent over a distance of %f meters."%(total_error/total_dist, total_dist));
90 if __name__ ==
'__main__':
91 rostest.run(PKG, sys.argv[0], XY_GT, sys.argv)