check_pose.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 
39 
40 PKG = 'pr2_gazebo'
41 NAME = 'check_pose'
42 
43 import math
44 import roslib
45 roslib.load_manifest(PKG)
46 
47 import sys, unittest
48 import os, os.path, threading, time
49 import rospy, rostest
50 from std_msgs.msg import *
51 from nav_msgs.msg import *
52 from tf.transformations import *
53 from numpy import *
54 
55 
56 GRP_CMD_POS = 0.03
57 
58 TARGET_DURATION = 1.0
59 ROT_TARGET_TOL = 0.01 #empirical test result john - 20090110
60 POS_TARGET_TOL = 0.01 #empirical test result john - 20090110
61 TEST_TIMEOUT = 100.0
62 
63 # pre-recorded poses for above commands
64 TARGET_BASE_TX = 2.0
65 TARGET_BASE_TY = 2.0
66 TARGET_BASE_TZ = 0.0
67 TARGET_BASE_QX = 0.0
68 TARGET_BASE_QY = 0.0
69 TARGET_BASE_QZ = 0.0
70 TARGET_BASE_QW = 1.0
71 
72 class PoseTest(unittest.TestCase):
73  def __init__(self, *args):
74  super(PoseTest, self).__init__(*args)
75  self.base_success = False
76  self.reached_target_base = False
78 
79  def printP3D(self, p3d):
80  print("pose ground truth received")
81  print("P3D pose translan: " + "x: " + str(p3d.pose.pose.position.x))
82  print(" " + "y: " + str(p3d.pos.position.y))
83  print(" " + "z: " + str(p3d.pose.pose.position.z))
84  print("P3D pose rotation: " + "x: " + str(p3d.pose.pose.orientation.x))
85  print(" " + "y: " + str(p3d.pose.pose.orientation.y))
86  print(" " + "z: " + str(p3d.pose.pose.orientation.z))
87  print(" " + "w: " + str(p3d.pose.pose.orientation.w))
88  print("P3D rate translan: " + "x: " + str(p3d.vel.vel.vx))
89  print(" " + "y: " + str(p3d.vel.vel.vy))
90  print(" " + "z: " + str(p3d.vel.vel.vz))
91  print("P3D rate rotation: " + "x: " + str(p3d.vel.ang_vel.vx))
92  print(" " + "y: " + str(p3d.vel.ang_vel.vy))
93  print(" " + "z: " + str(p3d.vel.ang_vel.vz))
94 
95  def baseP3dInput(self, p3d):
96  i = 0
97  pos_error = abs(p3d.pose.pose.position.x - TARGET_BASE_TX) + \
98  abs(p3d.pose.pose.position.y - TARGET_BASE_TY) + \
99  abs(p3d.pose.pose.position.z - TARGET_BASE_TZ) * 0 # ignore BASE_Z
100 
101  #target pose rotation matrix
102  target_q = [TARGET_BASE_QX \
103  ,TARGET_BASE_QY \
104  ,TARGET_BASE_QZ \
105  ,TARGET_BASE_QW]
106 
107  #p3d pose quaternion
108  p3d_q = [p3d.pose.pose.orientation.x \
109  ,p3d.pose.pose.orientation.y \
110  ,p3d.pose.pose.orientation.z \
111  ,p3d.pose.pose.orientation.w]
112 
113  # get error euler angles by inverting the target rotation matrix and multiplying by p3d quaternion
114  target_q_inv = quaternion_inverse(target_q)
115  rot_euler = euler_from_quaternion( quaternion_multiply(p3d_q, target_q_inv) )
116  rot_error = abs( rot_euler[0] ) + \
117  abs( rot_euler[1] ) + \
118  abs( rot_euler[2] )
119 
120  print(" base Error pos: " + str(pos_error) + " rot: " + str(rot_error))
121 
122  #self.printP3D(p3d) #for getting new valid data
123 
124  # has to reach target vw and maintain target vw for a duration of TARGET_DURATION seconds
125  if self.reached_target_base:
126  print(" base duration: " + str(time.time() - self.duration_start_base))
127  if rot_error < ROT_TARGET_TOL and pos_error < POS_TARGET_TOL:
128  if time.time() - self.duration_start_base > TARGET_DURATION:
129  self.base_success = True
130  else:
131  # failed to maintain target vw, reset duration
132  self.base_success = False
133  self.reached_target_base = False
134  else:
135  if rot_error < ROT_TARGET_TOL and pos_error < POS_TARGET_TOL:
136  print('success base')
137  self.reached_target_base = True
138  self.duration_start_base = time.time()
139 
140  def test_arm(self):
141  print("LNK\n")
142  rospy.Subscriber("/base_pose_ground_truth", Odometry, self.baseP3dInput)
143  rospy.init_node(NAME, anonymous=True)
144  timeout_t = time.time() + TEST_TIMEOUT
145  while not rospy.is_shutdown() and not self.base_success and time.time() < timeout_t:
146  time.sleep(1.0)
147  self.assert_(self.base_success)
148 if __name__ == '__main__':
149  rostest.run(PKG, sys.argv[0], PoseTest, sys.argv) #, text_mode=True)
msg
check_pose.PoseTest.reached_target_base
reached_target_base
Definition: check_pose.py:76
transformations
check_pose.PoseTest.baseP3dInput
def baseP3dInput(self, p3d)
Definition: check_pose.py:95
check_pose.PoseTest.duration_start_base
duration_start_base
Definition: check_pose.py:77
check_pose.PoseTest
Definition: check_pose.py:72
check_pose.PoseTest.__init__
def __init__(self, *args)
Definition: check_pose.py:73
msg
check_pose.PoseTest.test_arm
def test_arm(self)
Definition: check_pose.py:140
check_pose.PoseTest.base_success
base_success
Definition: check_pose.py:75
check_pose.PoseTest.printP3D
def printP3D(self, p3d)
Definition: check_pose.py:79


pr2_gazebo
Author(s): John Hsu
autogenerated on Sun Apr 17 2022 02:26:38