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, zeros, pi 00035 import rospy 00036 00037 class SingleTransform: 00038 def __init__(self, config = [0, 0, 0, 0, 0, 0]): 00039 assert(len(config) == 6) 00040 00041 eval_config = [eval(str(x)) for x in config] 00042 00043 self._config = reshape(matrix(eval_config, float), (-1,1)) 00044 00045 rospy.logdebug("Initializing single transform with params [%s]", ", ".join(["% 2.4f" % x for x in eval_config])) 00046 self.inflate(self._config) 00047 00048 def calc_free(self, free_config): 00049 assert( len(free_config) == 6 ) 00050 return [x == 1 for x in free_config] 00051 00052 00053 def params_to_config(self, param_vec): 00054 assert(param_vec.shape == (6,1)) 00055 return param_vec.T.tolist()[0] 00056 00057 # Convert column vector of params into config 00058 def inflate(self, p): 00059 assert(p.size == 6) 00060 00061 self._config = p.copy() # Once we can back compute p from T, we don't need _config 00062 00063 # Init output matrix 00064 T = matrix( zeros((4,4), float )) 00065 T[3,3] = 1.0 00066 00067 # Copy position into matrix 00068 T[0:3,3] = p[0:3,0] 00069 00070 # Renormalize the rotation axis to be unit length 00071 U,S,Vt = numpy.linalg.svd(p[3:6,0]) 00072 a = U[:,0] 00073 rot_angle= S[0]*Vt[0,0] 00074 00075 # Built rotation matrix 00076 c = cos(rot_angle) ; 00077 s = sin(rot_angle) ; 00078 00079 R = matrix( [ [ a[0,0]**2+(1-a[0,0]**2)*c, a[0,0]*a[1,0]*(1-c)-a[2,0]*s, a[0,0]*a[2,0]*(1-c)+a[1,0]*s], 00080 [a[0,0]*a[1,0]*(1-c)+a[2,0]*s, a[1,0]**2+(1-a[1,0]**2)*c, a[1,0]*a[2,0]*(1-c)-a[0,0]*s], 00081 [a[0,0]*a[2,0]*(1-c)-a[1,0]*s, a[1,0]*a[2,0]*(1-c)+a[0,0]*s, a[2,0]**2+(1-a[2,0]**2)*c] ] ) 00082 00083 T[0:3,0:3] = R ; 00084 self.transform = T 00085 00086 # Take transform, and convert into 6 param vector 00087 def deflate(self): 00088 # todo: This currently a hacky stub. To be correct, this should infer the parameter vector from the 4x4 transform 00089 return self._config 00090 00091 # Returns # of params needed for inflation & deflation 00092 def get_length(self): 00093 return 6 00094