$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, pi, array 00035 import rospy 00036 00037 class DhChain: 00038 def __init__(self, config = [[0,0,0,0]]): 00039 # Determine number of links 00040 00041 #import code; code.interact(local=locals()) 00042 self._M = len(config['dh']) 00043 rospy.logdebug("Initializing dh chain with [%u] links", self._M) 00044 00045 param_mat = numpy.matrix([ [eval(str(x)) for x in y] for y in config['dh']], float) 00046 assert(self._M*4 == param_mat.size) 00047 self._length = param_mat.size # The number of params needed to configure this chain 00048 self._config = param_mat # Mx4 matrix. Each row is a link, containing [theta, alpha, a, d] 00049 00050 self._cov_dict = config['cov'] 00051 self._gearing = config['gearing'] 00052 assert( len(self._cov_dict['joint_angles']) == self._M) 00053 00054 def calc_free(self, free_config): 00055 #import code; code.interact(local=locals()) 00056 assert( len(free_config['dh']) == self._M) 00057 assert( len(free_config['gearing']) == self._M ) 00058 00059 # Flatten the config 00060 flat_config = sum(free_config['dh'], []) 00061 00062 assert( len(flat_config) == self._M * 4) 00063 00064 flat_config = flat_config + free_config['gearing'] 00065 00066 # Convert int list into bool list 00067 flat_free = [x == 1 for x in flat_config] 00068 00069 return flat_free 00070 00071 def params_to_config(self, param_vec): 00072 assert(param_vec.shape == (self._M * 5, 1)) # 4 dh params + 1 gearing per joint 00073 dh_param_vec = param_vec[0:(self._M * 4),0] 00074 gearing_param_vec = param_vec[(self._M * 4):,0] 00075 00076 param_mat = reshape( dh_param_vec.T, (-1,4)) 00077 config_dict = {} 00078 config_dict['dh'] = param_mat.tolist() 00079 config_dict['gearing'] = (array(gearing_param_vec)[:,0]).tolist() 00080 config_dict['cov'] = self._cov_dict 00081 return config_dict 00082 00083 # Convert column vector of params into config 00084 def inflate(self, param_vec): 00085 param_mat = param_vec[:self._M*4,:] 00086 self._config = reshape(param_mat, (-1,4)) 00087 self._gearing = array(param_vec[self._M*4:,:])[:,0].tolist() 00088 00089 # Return column vector of config 00090 def deflate(self): 00091 param_vec = reshape(self._config, (-1,1)) 00092 param_vec = numpy.concatenate([param_vec, matrix(self._gearing).T]) 00093 return param_vec 00094 00095 # Returns # of params needed for inflation & deflation 00096 def get_length(self): 00097 return self._M*5 00098 00099 # Returns 4x4 numpy matrix of the pose of the tip of 00100 # the specified link num. Assumes the last link's tip 00101 # when link_num < 0 00102 def fk(self, chain_state, link_num=-1): 00103 if link_num < 0: 00104 link_num = self._M 00105 00106 dh_trimmed = self._config[0:(link_num+1), :] 00107 pos_trimmed = chain_state.position[0:(link_num+1)] 00108 gearing_trimmed = self._gearing[0:(link_num+1)] 00109 00110 pos_scaled = [cur_pos * cur_gearing for cur_pos, cur_gearing in zip(pos_trimmed, gearing_trimmed)] 00111 00112 eef_pose = chain_T(dh_trimmed, pos_scaled) 00113 return eef_pose 00114 00115 # Computes the transform for a chain 00116 # dh_params: Mx4 matrix, where M is the # of links in the model 00117 # Each row represents a link [theta, alpha, a, d] 00118 # joint_pos: 00119 # returns: 4x4 numpy matrix 00120 def chain_T(dh_params, joint_pos): 00121 if numpy.mod(dh_params.size,4) != 0: 00122 raise Exception("input size must be of length multiple of 4. Current is %s = %u" % (dh_params.shape, dh_params.size)) 00123 M = dh_params.size/4 00124 00125 if len(joint_pos) != M: 00126 raise Exception("joint_positions must length must be [%u]. Currently is [%u]" % (M, len(joint_pos))) 00127 00128 # Reshape input to be Nx4 00129 dh_final = numpy.array(dh_params.copy()) 00130 dh_final.shape = (M, 4) 00131 00132 for m in range(0,M): 00133 dh_final[m,0] = dh_final[m,0]+joint_pos[m] 00134 00135 # Mutliply all the dh links together (T0 * T1 * T2 * ... * TN) 00136 return reduce( lambda x,y: x*y, [ link_T(r[0]) for r in vsplit(dh_final, M)] ) 00137 00138 # Computes the 4x4 transformation matrix for a given set of dh 00139 # parameters. 00140 # dh_params - params of the form (theta(i), alpha(i), a(i), d(i)) 00141 # Output, a 4x4 transform from link (i-1) to (i) 00142 def link_T(dh_params): 00143 #print "DH: %s" % dh_params 00144 theta = dh_params[0] 00145 alpha = dh_params[1] 00146 a = dh_params[2] 00147 d = dh_params[3] 00148 00149 T_theta = matrix([ [ cos(theta), -sin(theta), 0, 0 ], 00150 [ sin(theta), cos(theta), 0, 0 ], 00151 [ 0, 0, 1, 0 ], 00152 [ 0, 0, 0, 1 ] ]) 00153 00154 T_alpha = matrix([ [ 1, 0, 0, 0 ], 00155 [ 0, cos(alpha), -sin(alpha), 0 ], 00156 [ 0, sin(alpha), cos(alpha), 0 ], 00157 [ 0, 0, 0, 1 ] ]) 00158 00159 T_trans = matrix([ [ 1, 0, 0, a ], 00160 [ 0, 1, 0, 0 ], 00161 [ 0, 0, 1, d ], 00162 [ 0, 0, 0, 1 ] ]) 00163 00164 return T_theta * T_trans * T_alpha