Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00037 PKG = 'pr2_gazebo'
00038 NAME = 'test_base_odomw_gt'
00039 
00040 import math
00041 import roslib
00042 roslib.load_manifest(PKG)
00043 
00044 import sys, unittest
00045 import os, time
00046 import rospy, rostest
00047 from geometry_msgs.msg import Twist,Vector3
00048 from nav_msgs.msg import Odometry
00049 
00050 TEST_DURATION   = 10.0
00051 
00052 TARGET_VX       =  0.0
00053 TARGET_VY       =  0.0
00054 TARGET_VW       =  0.5
00055 TARGET_DURATION = 2.0
00056 TARGET_TOL      = 0.2
00057 
00058 from test_base import BaseTest, Q, E
00059 class W_GT(BaseTest):
00060     def __init__(self, *args):
00061         super(W_GT, self).__init__(*args)
00062 
00063     def test_base(self):
00064         self.init_ros(NAME)
00065         timeout_t = time.time() + TEST_DURATION
00066         while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
00067             
00068             if self.p3d_initialized == True and self.odom_initialized == True:
00069               self.pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
00070             time.sleep(0.1)
00071             
00072             
00073             error = E(0,0,0)
00074             error.shortest_euler_distance(self.p3d_e,self.odom_e)
00075             print " error   " +      " x:" + str(self.odom_x - self.p3d_x) \
00076                               +      " y:" + str(self.odom_y - self.p3d_y) \
00077                               +      " e:" + str(error.x) + "," + str(error.y) + "," + str(error.z) \
00078                               + " t_odom:" + str(self.odom_e.z) + " t_p3d:" + str(self.p3d_e.z)
00079 
00080         
00081         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)
00082         print "total error:" + str(total_error) + " tol:" + str(TARGET_TOL)
00083         if total_error < TARGET_TOL:
00084             self.success = True
00085 
00086         self.assert_(self.success)
00087         
00088 if __name__ == '__main__':
00089     rostest.run(PKG, sys.argv[0], W_GT, sys.argv) 
00090 
00091