test_base_odomxy_gt.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Software License Agreement (BSD License)
3 #
4 # Copyright (c) 2008, Willow Garage, Inc.
5 # All rights reserved.
6 #
7 # Redistribution and use in source and binary forms, with or without
8 # modification, are permitted provided that the following conditions
9 # are met:
10 #
11 # * Redistributions of source code must retain the above copyright
12 # notice, this list of conditions and the following disclaimer.
13 # * Redistributions in binary form must reproduce the above
14 # copyright notice, this list of conditions and the following
15 # disclaimer in the documentation and/or other materials provided
16 # with the distribution.
17 # * Neither the name of the Willow Garage nor the names of its
18 # contributors may be used to endorse or promote products derived
19 # from this software without specific prior written permission.
20 #
21 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 # POSSIBILITY OF SUCH DAMAGE.
33 #
34 
35 ## Gazebo test base controller vw
36 
37 PKG = 'pr2_gazebo'
38 NAME = 'test_base_odomxy_gt'
39 
40 import math
41 import roslib
42 roslib.load_manifest(PKG)
43 
44 import sys, unittest
45 import os, os.path, threading, time
46 import rospy, rostest
47 from geometry_msgs.msg import Twist,Vector3
48 from nav_msgs.msg import Odometry
49 
50 TEST_DURATION = 10.0
51 
52 TARGET_VX = 0.25
53 TARGET_VY = 0.25
54 TARGET_VW = 0.0
55 TARGET_DURATION = 2.0
56 TARGET_TOL = 0.1 # in percentage of absolute distance
57 
58 from test_base import BaseTest, E, Q
59 class XY_GT(BaseTest):
60  def __init__(self, *args):
61  super(XY_GT, self).__init__(*args)
62 
63  def test_base(self):
64  self.init_ros(NAME)
65  timeout_t = None
66  while not rospy.is_shutdown() and not self.success and ( timeout_t is None or time.time() < timeout_t ) :
67  #do not start commanding base until p3d and odom are initialized
68  if self.p3d_initialized == True and self.odom_initialized == True:
69  self.pub.publish(Twist(Vector3(TARGET_VX,TARGET_VY, 0), Vector3(0,0,TARGET_VW)))
70  if timeout_t is None: # initialize timeout_t when p3d and odom is received
71  timeout_t = time.time() + TEST_DURATION
72  time.sleep(0.001)
73  #self.debug_pos()
74  # display what the odom error is
75  # print " error " + " x: " + str(self.odom_x - self.p3d_x) + " y: " + str(self.odom_y - self.p3d_y) + " t: " + str(self.odom_t - self.p3d_t)
76 
77  # check total error
78  total_error = abs(self.odom_x - self.p3d_x) + abs(self.odom_y - self.p3d_y) + abs(self.odom_t - self.p3d_t)
79  total_dist = math.sqrt(self.p3d_x*self.p3d_x + self.p3d_y*self.p3d_y + self.p3d_t*self.p3d_t)
80  if total_error/total_dist < TARGET_TOL:
81  self.success = True
82 
83  if not self.success:
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));
85  else:
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));
87 
88  self.assert_(self.success)
89 
90 if __name__ == '__main__':
91  rostest.run(PKG, sys.argv[0], XY_GT, sys.argv) #, text_mode=True)
92 
93 
def init_ros(self, name)
Definition: test_base.py:209


pr2_gazebo
Author(s): John Hsu
autogenerated on Fri May 3 2019 02:24:27