check_pose.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 arm controller
00036 ##   sends posision
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 = 'check_pose'
00042 
00043 import math
00044 import roslib
00045 roslib.load_manifest(PKG)
00046 
00047 import sys, unittest
00048 import os, os.path, threading, time
00049 import rospy, rostest
00050 from std_msgs.msg import *
00051 from nav_msgs.msg import *
00052 from tf.transformations import *
00053 from numpy import *
00054 
00055 
00056 GRP_CMD_POS     = 0.03
00057 
00058 TARGET_DURATION = 1.0
00059 ROT_TARGET_TOL      = 0.01  #empirical test result john - 20090110
00060 POS_TARGET_TOL      = 0.01  #empirical test result john - 20090110
00061 TEST_TIMEOUT    = 100.0
00062 
00063 # pre-recorded poses for above commands
00064 TARGET_BASE_TX     = 2.0
00065 TARGET_BASE_TY     = 2.0
00066 TARGET_BASE_TZ     = 0.0
00067 TARGET_BASE_QX     = 0.0
00068 TARGET_BASE_QY     = 0.0
00069 TARGET_BASE_QZ     = 0.0
00070 TARGET_BASE_QW     = 1.0
00071 
00072 class PoseTest(unittest.TestCase):
00073     def __init__(self, *args):
00074         super(PoseTest, self).__init__(*args)
00075         self.base_success = False
00076         self.reached_target_base = False
00077         self.duration_start_base = 0
00078 
00079     def printP3D(self, p3d):
00080         print "pose ground truth received"
00081         print "P3D pose translan: " + "x: " + str(p3d.pose.pose.position.x)
00082         print "                   " + "y: " + str(p3d.pos.position.y)
00083         print "                   " + "z: " + str(p3d.pose.pose.position.z)
00084         print "P3D pose rotation: " + "x: " + str(p3d.pose.pose.orientation.x)
00085         print "                   " + "y: " + str(p3d.pose.pose.orientation.y)
00086         print "                   " + "z: " + str(p3d.pose.pose.orientation.z)
00087         print "                   " + "w: " + str(p3d.pose.pose.orientation.w)
00088         print "P3D rate translan: " + "x: " + str(p3d.vel.vel.vx)
00089         print "                   " + "y: " + str(p3d.vel.vel.vy)
00090         print "                   " + "z: " + str(p3d.vel.vel.vz)
00091         print "P3D rate rotation: " + "x: " + str(p3d.vel.ang_vel.vx)
00092         print "                   " + "y: " + str(p3d.vel.ang_vel.vy)
00093         print "                   " + "z: " + str(p3d.vel.ang_vel.vz)
00094 
00095     def baseP3dInput(self, p3d):
00096         i = 0
00097         pos_error = abs(p3d.pose.pose.position.x - TARGET_BASE_TX) + \
00098                     abs(p3d.pose.pose.position.y - TARGET_BASE_TY) + \
00099                     abs(p3d.pose.pose.position.z - TARGET_BASE_TZ)
00100 
00101         #target pose rotation matrix
00102         target_q = [TARGET_BASE_QX  \
00103                    ,TARGET_BASE_QY  \
00104                    ,TARGET_BASE_QZ  \
00105                    ,TARGET_BASE_QW]
00106 
00107         #p3d pose quaternion
00108         p3d_q     = [p3d.pose.pose.orientation.x  \
00109                     ,p3d.pose.pose.orientation.y  \
00110                     ,p3d.pose.pose.orientation.z  \
00111                     ,p3d.pose.pose.orientation.w]
00112 
00113         # get error euler angles by inverting the target rotation matrix and multiplying by p3d quaternion
00114         target_q_inv = quaternion_inverse(target_q)
00115         rot_euler = euler_from_quaternion( quaternion_multiply(p3d_q, target_q_inv) )
00116         rot_error = abs( rot_euler[0] ) + \
00117                     abs( rot_euler[1] ) + \
00118                     abs( rot_euler[2] )
00119 
00120         print " base Error pos: " + str(pos_error) + " rot: " + str(rot_error)
00121 
00122         #self.printP3D(p3d) #for getting new valid data
00123 
00124         # has to reach target vw and maintain target vw for a duration of TARGET_DURATION seconds
00125         if self.reached_target_base:
00126           print " base duration: " + str(time.time() - self.duration_start_base)
00127           if rot_error < ROT_TARGET_TOL and pos_error < POS_TARGET_TOL:
00128             if time.time() - self.duration_start_base > TARGET_DURATION:
00129               self.base_success = True
00130           else:
00131             # failed to maintain target vw, reset duration
00132             self.base_success = False
00133             self.reached_target_base = False
00134         else:
00135           if rot_error < ROT_TARGET_TOL and pos_error < POS_TARGET_TOL:
00136             print 'success base'
00137             self.reached_target_base = True
00138             self.duration_start_base = time.time()
00139     
00140     def test_arm(self):
00141         print "LNK\n"
00142         rospy.Subscriber("/base_pose_ground_truth", Odometry, self.baseP3dInput)
00143         rospy.init_node(NAME, anonymous=True)
00144         timeout_t = time.time() + TEST_TIMEOUT
00145         while not rospy.is_shutdown() and not self.base_success and time.time() < timeout_t:
00146             time.sleep(1.0)
00147         self.assert_(self.base_success)
00148 if __name__ == '__main__':
00149     rostest.run(PKG, sys.argv[0], PoseTest, sys.argv) #, text_mode=True)


pr2_gazebo
Author(s): John Hsu
autogenerated on Sat Sep 5 2015 11:23:01