test_base_vw_gt.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # Software License Agreement (BSD License)
00003 #
00004 # Copyright (c) 2008, Willow Garage, Inc.
00005 # All rights reserved.
00006 #
00007 # Redistribution and use in source and binary forms, with or without
00008 # modification, are permitted provided that the following conditions
00009 # are met:
00010 #
00011 #  * Redistributions of source code must retain the above copyright
00012 #    notice, this list of conditions and the following disclaimer.
00013 #  * Redistributions in binary form must reproduce the above
00014 #    copyright notice, this list of conditions and the following
00015 #    disclaimer in the documentation and/or other materials provided
00016 #    with the distribution.
00017 #  * Neither the name of the Willow Garage nor the names of its
00018 #    contributors may be used to endorse or promote products derived
00019 #    from this software without specific prior written permission.
00020 #
00021 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 # POSSIBILITY OF SUCH DAMAGE.
00033 #
00034 
00035 ## Gazebo test base controller vw
00036 ##   sends cmd_vel vx= 0, vy=0, vw =TARGET_VW
00037 ##   checks to see if P3D returns corresponding ground truth within TARGET_TOL of TARGET_VW
00038 ##          for a duration of TARGET_DURATION seconds
00039 
00040 PKG = 'pr2_gazebo'
00041 NAME = 'test_base_vw_gt'
00042 
00043 import math
00044 import roslib
00045 roslib.load_manifest(PKG)
00046 
00047 import sys, unittest
00048 import os, time
00049 import rospy, rostest
00050 from geometry_msgs.msg import Twist,Vector3
00051 from nav_msgs.msg import Odometry
00052 
00053 TEST_DURATION   = 60.0
00054 
00055 TARGET_VW       =  0.5
00056 TARGET_DURATION = 2.0
00057 #TARGET_TOL      = 0.15 #empirical test result john - 20090420
00058 TARGET_TOL      = 0.18 #empirical test result john - 20120810 - slight regression
00059 
00060 from test_base import BaseTest, Q, E
00061 class VW_GT(BaseTest):
00062     def __init__(self, *args):
00063         super(VW_GT, self).__init__(*args)
00064         self.reached_target_vw = False
00065         self.duration_start = 0
00066 
00067     def odomInput(self, odom):
00068         # override parent
00069         #self.printBaseOdom(odom)
00070         error = 0
00071 
00072     def p3dInput(self, p3d):
00073         # override parent
00074         i = 0
00075         #self.printBaseP3D(p3d)
00076         error = abs(p3d.twist.twist.angular.z - TARGET_VW)
00077         print " Error: " + str(error) + " Duration: " + str(time.time() - self.duration_start)
00078         # has to reach target vw and maintain target vw for a duration of TARGET_DURATION seconds
00079         if self.reached_target_vw:
00080           if error < TARGET_TOL:
00081             if time.time() - self.duration_start > TARGET_DURATION:
00082               self.success = True
00083           else:
00084             # failed to maintain target vw, reset duration
00085             self.success = False
00086             self.reached_target_vw = False
00087         else:
00088           if error < TARGET_TOL:
00089             self.reached_target_vw = True
00090             self.duration_start = time.time()
00091     
00092     def test_base(self):
00093         self.init_ros(NAME)
00094         timeout_t = time.time() + TEST_DURATION
00095         while not rospy.is_shutdown() and not self.success and time.time() < timeout_t:
00096             self.pub.publish(Twist(Vector3(0.0,0.0,0), Vector3(0,0,TARGET_VW)))
00097             time.sleep(0.1)
00098         self.assert_(self.success)
00099         
00100 if __name__ == '__main__':
00101     rostest.run(PKG, sys.argv[0], VW_GT, sys.argv) #, text_mode=True)
00102 
00103 


pr2_gazebo
Author(s): John Hsu
autogenerated on Thu Apr 24 2014 15:48:38