38 NAME =
'test_base_odomw_gt' 42 roslib.load_manifest(PKG)
43 roslib.load_manifest(
'rostest')
48 from geometry_msgs.msg
import Twist,Vector3
60 from test_base
import BaseTest, Q, E
68 while not rospy.is_shutdown()
and not self.
success and ( timeout_t
is None or time.time() < timeout_t ) :
71 self.pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
73 timeout_t = time.time() + TEST_DURATION
78 error.shortest_euler_distance(self.
p3d_e,self.
odom_e)
86 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)
89 if total_error/total_dist < TARGET_TOL:
93 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));
95 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));
99 if __name__ ==
'__main__':
100 rostest.run(PKG, sys.argv[0], XYW_GT, sys.argv)