$search
00001 # Software License Agreement (BSD License) 00002 # 00003 # Copyright (c) 2008, Willow Garage, Inc. 00004 # All rights reserved. 00005 # 00006 # Redistribution and use in source and binary forms, with or without 00007 # modification, are permitted provided that the following conditions 00008 # are met: 00009 # 00010 # * Redistributions of source code must retain the above copyright 00011 # notice, this list of conditions and the following disclaimer. 00012 # * Redistributions in binary form must reproduce the above 00013 # copyright notice, this list of conditions and the following 00014 # disclaimer in the documentation and/or other materials provided 00015 # with the distribution. 00016 # * Neither the name of Willow Garage, Inc. nor the names of its 00017 # contributors may be used to endorse or promote products derived 00018 # from this software without specific prior written permission. 00019 # 00020 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00021 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00022 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00023 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00024 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00025 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00026 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00027 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00028 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00029 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00030 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00031 # POSSIBILITY OF SUCH DAMAGE. 00032 00033 import numpy 00034 from numpy import matrix, vsplit, sin, cos, reshape 00035 import rospy 00036 from pr2_calibration_estimation.single_transform import SingleTransform 00037 00038 # Primitive used to model PR2's tilting laser platform. Consists of 2 fixed transforms. 00039 # One before the joint, and one after. The joint axis is the x-axis after the first transform 00040 00041 class TiltingLaser: 00042 00043 # Dictionary with two elems (Total of 13 elems) 00044 # before_joint: [px py pz rx ry rx] 00045 # after_joint: [px py pz rx ry rx] 00046 def __init__(self, config = {"before_joint": [ 0, 0, 0, 0, 0, 0], 00047 "after_joint" : [ 0, 0, 0, 0, 0, 0], 00048 'gearing':1 } ): 00049 rospy.logdebug("Initializing tilting laser") 00050 00051 self._before_joint = SingleTransform() 00052 self._after_joint = SingleTransform() 00053 00054 if 'cov' in config.keys(): 00055 self._cov_dict = config['cov'] 00056 else: 00057 self._cov_dict = {} 00058 00059 param_vec = self.dict_to_params(config) 00060 self.inflate(param_vec) 00061 00062 def dict_to_params(self, config): 00063 param_vec = reshape(matrix([ config["before_joint"], config["after_joint"] ], float), (-1,1)) 00064 param_vec = numpy.concatenate([param_vec, matrix([config["gearing"]])]) 00065 assert(param_vec.size == self.get_length()) 00066 return param_vec 00067 00068 def params_to_config(self, param_vec): 00069 assert(param_vec.shape == (13,1)) 00070 return {"before_joint" : self._before_joint.params_to_config(param_vec[0:6, 0]), 00071 "after_joint" : self._before_joint.params_to_config(param_vec[6:12,0]), 00072 "gearing" : float(param_vec[12,0]), 00073 "cov" : self._cov_dict} 00074 00075 def calc_free(self, free_config): 00076 #import code; code.interact(local=locals()) 00077 assert( 'before_joint' in free_config ) 00078 assert( 'after_joint' in free_config ) 00079 assert( 'gearing' in free_config ) 00080 00081 # Flatten the config 00082 flat_config = free_config['before_joint'] + free_config['after_joint'] + [free_config['gearing']] 00083 assert( len(flat_config) == self.get_length()) 00084 00085 # Convert int list into bool list 00086 flat_free = [x == 1 for x in flat_config] 00087 00088 return flat_free 00089 00090 # Convert column vector of params into config 00091 def inflate(self, param_vec): 00092 self._before_joint.inflate(param_vec[0:6,:]) 00093 self._after_joint.inflate(param_vec[6:12,:]) 00094 self._gearing = param_vec[12,0] 00095 00096 # Return column vector of config 00097 def deflate(self): 00098 param_vec = matrix(numpy.zeros((13,1), float)) 00099 param_vec[0:6,0] = self._before_joint.deflate() 00100 param_vec[6:12,0] = self._after_joint.deflate() 00101 param_vec[12,0] = self._gearing 00102 return param_vec 00103 00104 # Returns # of params needed for inflation & deflation 00105 def get_length(self): 00106 return 13 00107 00108 def compute_pose(self, joint_pos): 00109 joint_T = SingleTransform([0, 0, 0, 0, joint_pos[0]*self._gearing, 0]) 00110 return self._before_joint.transform * joint_T.transform * self._after_joint.transform 00111 00112 # Given a single set of joint positions, project into 3D 00113 # joint_pos - a single list that looks like [tilting_joint, pointing_angle, range] 00114 # returns - 4x1 numpy matrix, with the resulting projected point (in homogenous coords) 00115 def project_point_to_3D(self, joint_pos): 00116 p = joint_pos[1] # Pointing Angle 00117 r = joint_pos[2] # Range 00118 ray = reshape(matrix([cos(p)*r, sin(p)*r, 0, 1]), (-1,1)) 00119 00120 result = self.compute_pose(joint_pos) * ray 00121 return result 00122 00123 # Take sets of joint positions, and project them into 3D 00124 # joint_positions - should look like the following 00125 # - [tilting_joint, pointing_angle, range] # Point 1 00126 # - [tilting_joint, pointing_angle, range] # Point 2 00127 # - : 00128 # - [tilting_joint, pointing_angle, range] # Point N 00129 # Return - 4xN numpy matrix of 3D points 00130 def project_to_3D(self, joint_pos): 00131 result = numpy.concatenate( [self.project_point_to_3D(x) for x in joint_pos], 1 ) 00132 return result