kdl_kinematics.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 #
00003 # Provides wrappers for PyKDL kinematics.
00004 #
00005 # Copyright (c) 2012, Georgia Tech Research Corporation
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions are met:
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 copyright
00013 #       notice, this list of conditions and the following disclaimer in the
00014 #       documentation and/or other materials provided with the distribution.
00015 #     * Neither the name of the Georgia Tech Research Corporation nor the
00016 #       names of its contributors may be used to endorse or promote products
00017 #       derived from this software without specific prior written permission.
00018 #
00019 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00020 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00022 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00023 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00024 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00025 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00027 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00028 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00029 #
00030 # Author: Kelsey Hawkins
00031 
00032 import numpy as np
00033 
00034 import roslib
00035 roslib.load_manifest("pykdl_utils")
00036 
00037 import PyKDL as kdl
00038 import rospy
00039 
00040 import hrl_geom.transformations as trans
00041 from hrl_geom.pose_converter import PoseConv
00042 from kdl_parser import kdl_tree_from_urdf_model
00043 from urdf_parser_py.urdf import URDF
00044 
00045 def create_kdl_kin(base_link, end_link, urdf_filename=None):
00046     if urdf_filename is None:
00047         robot = URDF.load_from_parameter_server(verbose=False)
00048     else:
00049         robot = URDF.load_xml_file(urdf_filename, verbose=False)
00050     return KDLKinematics(robot, base_link, end_link)
00051 
00052 ##
00053 # Provides wrappers for performing KDL functions on a designated kinematic
00054 # chain given a URDF representation of a robot.
00055 
00056 class KDLKinematics(object):
00057     ##
00058     # Constructor
00059     # @param urdf URDF object of robot.
00060     # @param base_link Name of the root link of the kinematic chain.
00061     # @param end_link Name of the end link of the kinematic chain.
00062     # @param kdl_tree Optional KDL.Tree object to use. If None, one will be generated
00063     #                          from the URDF.
00064     def __init__(self, urdf, base_link, end_link, kdl_tree=None):
00065         if kdl_tree is None:
00066             kdl_tree = kdl_tree_from_urdf_model(urdf)
00067         self.tree = kdl_tree
00068         self.urdf = urdf
00069 
00070         base_link = base_link.split("/")[-1] # for dealing with tf convention
00071         end_link = end_link.split("/")[-1] # for dealing with tf convention
00072         self.chain = kdl_tree.getChain(base_link, end_link)
00073         self.base_link = base_link
00074         self.end_link = end_link
00075 
00076         # record joint information in easy-to-use lists
00077         self.joint_limits_lower = []
00078         self.joint_limits_upper = []
00079         self.joint_safety_lower = []
00080         self.joint_safety_upper = []
00081         self.joint_types = []
00082         for jnt_name in self.get_joint_names():
00083             jnt = urdf.joints[jnt_name]
00084             if jnt.limits is not None:
00085                 self.joint_limits_lower.append(jnt.limits.lower)
00086                 self.joint_limits_upper.append(jnt.limits.upper)
00087             else:
00088                 self.joint_limits_lower.append(None)
00089                 self.joint_limits_upper.append(None)
00090             if jnt.safety is not None:
00091                 self.joint_safety_lower.append(jnt.safety.lower)
00092                 self.joint_safety_upper.append(jnt.safety.upper)
00093             elif jnt.limits is not None:
00094                 self.joint_safety_lower.append(jnt.limits.lower)
00095                 self.joint_safety_upper.append(jnt.limits.upper)
00096             else:
00097                 self.joint_safety_lower.append(None)
00098                 self.joint_safety_upper.append(None)
00099             self.joint_types.append(jnt.joint_type)
00100         def replace_none(x, v):
00101             if x is None:
00102                 return v
00103             return x
00104         self.joint_limits_lower = np.array([replace_none(jl, -np.inf) 
00105                                             for jl in self.joint_limits_lower])
00106         self.joint_limits_upper = np.array([replace_none(jl, np.inf) 
00107                                             for jl in self.joint_limits_upper])
00108         self.joint_safety_lower = np.array([replace_none(jl, -np.inf) 
00109                                             for jl in self.joint_safety_lower])
00110         self.joint_safety_upper = np.array([replace_none(jl, np.inf) 
00111                                             for jl in self.joint_safety_upper])
00112         self.joint_types = np.array(self.joint_types)
00113         self.num_joints = len(self.get_joint_names())
00114 
00115         self._fk_kdl = kdl.ChainFkSolverPos_recursive(self.chain)
00116         self._ik_v_kdl = kdl.ChainIkSolverVel_pinv(self.chain)
00117         self._ik_p_kdl = kdl.ChainIkSolverPos_NR(self.chain, self._fk_kdl, self._ik_v_kdl)
00118         self._jac_kdl = kdl.ChainJntToJacSolver(self.chain)
00119         self._dyn_kdl = kdl.ChainDynParam(self.chain, kdl.Vector.Zero())
00120 
00121     ##
00122     # @return List of link names in the kinematic chain.
00123     def get_link_names(self, joints=False, fixed=True):
00124         return self.urdf.get_chain(self.base_link, self.end_link, joints, fixed)
00125 
00126     ##
00127     # @return List of joint names in the kinematic chain.
00128     def get_joint_names(self, links=False, fixed=False):
00129         return self.urdf.get_chain(self.base_link, self.end_link,
00130                                    links=links, fixed=fixed)
00131 
00132     def get_joint_limits(self):
00133         return self.joint_limits_lower, self.joint_limits_upper
00134 
00135     def FK(self, q, link_number=None):
00136         if link_number is not None:
00137             end_link = self.get_link_names(fixed=False)[link_number]
00138         else:
00139             end_link = None
00140         homo_mat = self.forward(q, end_link)
00141         pos, rot = PoseConv.to_pos_rot(homo_mat)
00142         return pos, rot
00143 
00144 
00145     ##
00146     # Forward kinematics on the given joint angles, returning the location of the
00147     # end_link in the base_link's frame.
00148     # @param q List of joint angles for the full kinematic chain.
00149     # @param end_link Name of the link the pose should be obtained for.
00150     # @param base_link Name of the root link frame the end_link should be found in.
00151     # @return 4x4 numpy.mat homogeneous transformation
00152     def forward(self, q, end_link=None, base_link=None):
00153         link_names = self.get_link_names()
00154         if end_link is None:
00155             end_link = self.chain.getNrOfSegments()
00156         else:
00157             end_link = end_link.split("/")[-1]
00158             if end_link in link_names:
00159                 end_link = link_names.index(end_link)
00160             else:
00161                 print "Target segment %s not in KDL chain" % end_link
00162                 return None
00163         if base_link is None:
00164             base_link = 0
00165         else:
00166             base_link = base_link.split("/")[-1]
00167             if base_link in link_names:
00168                 base_link = link_names.index(base_link)
00169             else:
00170                 print "Base segment %s not in KDL chain" % base_link
00171                 return None
00172         base_trans = self._do_kdl_fk(q, base_link)
00173         if base_trans is None:
00174             print "FK KDL failure on base transformation."
00175         end_trans = self._do_kdl_fk(q, end_link)
00176         if end_trans is None:
00177             print "FK KDL failure on end transformation."
00178         return base_trans**-1 * end_trans
00179 
00180     def _do_kdl_fk(self, q, link_number):
00181         endeffec_frame = kdl.Frame()
00182         kinematics_status = self._fk_kdl.JntToCart(joint_list_to_kdl(q),
00183                                                    endeffec_frame,
00184                                                    link_number)
00185         if kinematics_status >= 0:
00186             p = endeffec_frame.p
00187             M = endeffec_frame.M
00188             return np.mat([[M[0,0], M[0,1], M[0,2], p.x()], 
00189                            [M[1,0], M[1,1], M[1,2], p.y()], 
00190                            [M[2,0], M[2,1], M[2,2], p.z()],
00191                            [     0,      0,      0,     1]])
00192         else:
00193             return None
00194 
00195     ##
00196     # Inverse kinematics for a given pose, returning the joint angles required
00197     # to obtain the target pose.
00198     # @param pose Pose-like object represeting the target pose of the end effector.
00199     # @param q_guess List of joint angles to seed the IK search.
00200     # @param min_joints List of joint angles to lower bound the angles on the IK search.
00201     #                   If None, the safety limits are used.
00202     # @param max_joints List of joint angles to upper bound the angles on the IK search.
00203     #                   If None, the safety limits are used.
00204     # @return np.array of joint angles needed to reach the pose or None if no solution was found.
00205     def inverse(self, pose, q_guess=None, min_joints=None, max_joints=None):
00206         pos, rot = PoseConv.to_pos_rot(pose)
00207         pos_kdl = kdl.Vector(pos[0,0], pos[1,0], pos[2,0])
00208         rot_kdl = kdl.Rotation(rot[0,0], rot[0,1], rot[0,2],
00209                                rot[1,0], rot[1,1], rot[1,2],
00210                                rot[2,0], rot[2,1], rot[2,2])
00211         frame_kdl = kdl.Frame(rot_kdl, pos_kdl)
00212         if min_joints is None:
00213             min_joints = self.joint_safety_lower
00214         if max_joints is None:
00215             max_joints = self.joint_safety_upper
00216         mins_kdl = joint_list_to_kdl(min_joints)
00217         maxs_kdl = joint_list_to_kdl(max_joints)
00218         ik_p_kdl = kdl.ChainIkSolverPos_NR_JL(self.chain, mins_kdl, maxs_kdl, 
00219                                               self._fk_kdl, self._ik_v_kdl)
00220 
00221         if q_guess == None:
00222             # use the midpoint of the joint limits as the guess
00223             lower_lim = np.where(np.isfinite(min_joints), min_joints, 0.)
00224             upper_lim = np.where(np.isfinite(max_joints), max_joints, 0.)
00225             q_guess = (lower_lim + upper_lim) / 2.0
00226             q_guess = np.where(np.isnan(q_guess), [0.]*len(q_guess), q_guess)
00227 
00228         q_kdl = kdl.JntArray(self.num_joints)
00229         q_guess_kdl = joint_list_to_kdl(q_guess)
00230         if ik_p_kdl.CartToJnt(q_guess_kdl, frame_kdl, q_kdl) >= 0:
00231             return np.array(joint_kdl_to_list(q_kdl))
00232         else:
00233             return None
00234 
00235     ##
00236     # Repeats IK for different sets of random initial angles until a solution is found
00237     # or the call times out.
00238     # @param pose Pose-like object represeting the target pose of the end effector.
00239     # @param timeout Time in seconds to look for a solution.
00240     # @return np.array of joint angles needed to reach the pose or None if no solution was found.
00241     def inverse_search(self, pose, timeout=1.):
00242         st_time = rospy.get_time()
00243         while not rospy.is_shutdown() and rospy.get_time() - st_time < timeout:
00244             q_init = self.random_joint_angles()
00245             q_ik = self.inverse(pose, q_init)
00246             if q_ik is not None:
00247                 return q_ik
00248         return None
00249 
00250     ##
00251     # Returns the Jacobian matrix at the end_link for the given joint angles.
00252     # @param q List of joint angles.
00253     # @return 6xN np.mat Jacobian
00254     # @param pos Point in base frame where the jacobian is acting on.
00255     #            If None, we assume the end_link
00256     def jacobian(self, q, pos=None):
00257         j_kdl = kdl.Jacobian(self.num_joints)
00258         q_kdl = joint_list_to_kdl(q)
00259         self._jac_kdl.JntToJac(q_kdl, j_kdl)
00260         if pos is not None:
00261             ee_pos = self.forward(q)[:3,3]
00262             pos_kdl = kdl.Vector(pos[0]-ee_pos[0], pos[1]-ee_pos[1], 
00263                                   pos[2]-ee_pos[2])
00264             j_kdl.changeRefPoint(pos_kdl)
00265         return kdl_to_mat(j_kdl)
00266 
00267     ##
00268     # Returns the joint space mass matrix at the end_link for the given joint angles.
00269     # @param q List of joint angles.
00270     # @return NxN np.mat Inertia matrix
00271     def inertia(self, q):
00272         h_kdl = kdl.JntSpaceInertiaMatrix(self.num_joints)
00273         self._dyn_kdl.JntToMass(joint_list_to_kdl(q), h_kdl)
00274         return kdl_to_mat(h_kdl)
00275 
00276     ##
00277     # Returns the cartesian space mass matrix at the end_link for the given joint angles.
00278     # @param q List of joint angles.
00279     # @return 6x6 np.mat Cartesian inertia matrix
00280     def cart_inertia(self, q):
00281         H = self.inertia(q)
00282         J = self.jacobian(q)
00283         return np.linalg.inv(J * np.linalg.inv(H) * J.T)
00284 
00285     ##
00286     # Tests to see if the given joint angles are in the joint limits.
00287     # @param List of joint angles.
00288     # @return True if joint angles in joint limits.
00289     def joints_in_limits(self, q):
00290         lower_lim = self.joint_limits_lower
00291         upper_lim = self.joint_limits_upper
00292         return np.all([q >= lower_lim, q <= upper_lim], 0)
00293 
00294     ##
00295     # Tests to see if the given joint angles are in the joint safety limits.
00296     # @param List of joint angles.
00297     # @return True if joint angles in joint safety limits.
00298     def joints_in_safe_limits(self, q):
00299         lower_lim = self.joint_safety_lower
00300         upper_lim = self.joint_safety_upper
00301         return np.all([q >= lower_lim, q <= upper_lim], 0)
00302 
00303     ##
00304     # Clips joint angles to the safety limits.
00305     # @param List of joint angles.
00306     # @return np.array list of clipped joint angles.
00307     def clip_joints_safe(self, q):
00308         lower_lim = self.joint_safety_lower
00309         upper_lim = self.joint_safety_upper
00310         return np.clip(q, lower_lim, upper_lim)
00311 
00312     ##
00313     # Returns a set of random joint angles distributed uniformly in the safety limits.
00314     # @return np.array list of random joint angles.
00315     def random_joint_angles(self):
00316         lower_lim = self.joint_safety_lower
00317         upper_lim = self.joint_safety_upper
00318         lower_lim = np.where(np.isfinite(lower_lim), lower_lim, -np.pi)
00319         upper_lim = np.where(np.isfinite(upper_lim), upper_lim, np.pi)
00320         zip_lims = zip(lower_lim, upper_lim)
00321         return np.array([np.random.uniform(min_lim, max_lim) for min_lim, max_lim in zip_lims])
00322 
00323     ##
00324     # Returns a difference between the two sets of joint angles while insuring
00325     # that the shortest angle is returned for the continuous joints.
00326     # @param q1 List of joint angles.
00327     # @param q2 List of joint angles.
00328     # @return np.array of wrapped joint angles for retval = q1 - q2
00329     def difference_joints(self, q1, q2):
00330         diff = np.array(q1) - np.array(q2)
00331         diff_mod = np.mod(diff, 2 * np.pi)
00332         diff_alt = diff_mod - 2 * np.pi 
00333         for i, continuous in enumerate(self.joint_types == 'continuous'):
00334             if continuous:
00335                 if diff_mod[i] < -diff_alt[i]:
00336                     diff[i] = diff_mod[i]
00337                 else:
00338                     diff[i] = diff_alt[i]
00339         return diff
00340 
00341     ##
00342     # Performs an IK search while trying to balance the demands of reaching the goal,
00343     # maintaining a posture, and prioritizing rotation or position.
00344     def inverse_biased(self, pose, q_init, q_bias, q_bias_weights, rot_weight=1., 
00345                        bias_vel=0.01, num_iter=100):
00346         # This code is potentially volitile
00347         q_out = np.mat(self.inverse_search(pose)).T
00348         for i in range(num_iter):
00349             pos_fk, rot_fk = PoseConv.to_pos_rot(self.forward(q_out))
00350             delta_twist = np.mat(np.zeros((6, 1)))
00351             pos_delta = pos - pos_fk
00352             delta_twist[:3,0] = pos_delta
00353             rot_delta = np.mat(np.eye(4))
00354             rot_delta[:3,:3] = rot * rot_fk.T
00355             rot_delta_angles = np.mat(trans.euler_from_matrix(rot_delta)).T
00356             delta_twist[3:6,0] = rot_delta_angles
00357             J = self.jacobian(q_out)
00358             J[3:6,:] *= np.sqrt(rot_weight)
00359             delta_twist[3:6,0] *= np.sqrt(rot_weight)
00360             J_tinv = np.linalg.inv(J.T * J + np.diag(q_bias_weights) * np.eye(len(q_init))) * J.T
00361             q_bias_diff = q_bias - q_out
00362             q_bias_diff_normed = q_bias_diff * bias_vel / np.linalg.norm(q_bias_diff)
00363             delta_q = q_bias_diff_normed + J_tinv * (delta_twist - J * q_bias_diff_normed)
00364             q_out += delta_q 
00365             q_out = np.mat(self.clip_joints_safe(q_out.T.A[0])).T
00366         return q_out
00367 
00368     ##
00369     # inverse_biased with random restarts.
00370     def inverse_biased_search(self, pos, rot, q_bias, q_bias_weights, rot_weight=1., 
00371                               bias_vel=0.01, num_iter=100, num_search=20):
00372         # This code is potentially volitile
00373         q_sol_min = []
00374         min_val = 1000000.
00375         for i in range(num_search):
00376             q_init = self.random_joint_angles()
00377             q_sol = self.inverse_biased(pos, rot, q_init, q_bias, q_bias_weights, rot_weight=1., 
00378                                         bias_vel=bias_vel, num_iter=num_iter)
00379             cur_val = np.linalg.norm(np.diag(q_bias_weights) * (q_sol - q_bias)) 
00380             if cur_val < min_val:
00381                 min_val = cur_val
00382                 q_sol_min = q_sol
00383         return q_sol_min
00384         
00385 
00386 def kdl_to_mat(m):
00387     mat =  np.mat(np.zeros((m.rows(), m.columns())))
00388     for i in range(m.rows()):
00389         for j in range(m.columns()):
00390             mat[i,j] = m[i,j]
00391     return mat
00392 
00393 def joint_kdl_to_list(q):
00394     if q == None:
00395         return None
00396     return [q[i] for i in range(q.rows())]
00397 
00398 def joint_list_to_kdl(q):
00399     if q is None:
00400         return None
00401     if type(q) == np.matrix and q.shape[1] == 0:
00402         q = q.T.tolist()[0]
00403     q_kdl = kdl.JntArray(len(q))
00404     for i, q_i in enumerate(q):
00405         q_kdl[i] = q_i
00406     return q_kdl
00407 
00408 def main():
00409     import sys
00410     def usage():
00411         print("Tests for kdl_parser:\n")
00412         print("kdl_parser <urdf file>")
00413         print("\tLoad the URDF from file.")
00414         print("kdl_parser")
00415         print("\tLoad the URDF from the parameter server.")
00416         sys.exit(1)
00417 
00418     if len(sys.argv) > 2:
00419         usage()
00420     if len(sys.argv) == 2 and (sys.argv[1] == "-h" or sys.argv[1] == "--help"):
00421         usage()
00422     if (len(sys.argv) == 1):
00423         robot = URDF.load_from_parameter_server(verbose=False)
00424     else:
00425         robot = URDF.load_xml_file(sys.argv[1], verbose=False)
00426 
00427     if True:
00428         import random
00429         base_link = robot.get_root()
00430         end_link = robot.links.keys()[random.randint(0, len(robot.links)-1)]
00431         print "Root link: %s; Random end link: %s" % (base_link, end_link)
00432         kdl_kin = KDLKinematics(robot, base_link, end_link)
00433         q = kdl_kin.random_joint_angles()
00434         print "Random angles:", q
00435         pose = kdl_kin.forward(q)
00436         print "FK:", pose
00437         q_new = kdl_kin.inverse(pose)
00438         print "IK (not necessarily the same):", q_new
00439         if q_new is not None:
00440             pose_new = kdl_kin.forward(q_new)
00441             print "FK on IK:", pose_new
00442             print "Error:", np.linalg.norm(pose_new * pose**-1 - np.mat(np.eye(4)))
00443         else:
00444             print "IK failure"
00445         J = kdl_kin.jacobian(q)
00446         print "Jacobian:", J
00447         M = kdl_kin.inertia(q)
00448         print "Inertia matrix:", M
00449         if False:
00450             M_cart = kdl_kin.cart_inertia(q)
00451             print "Cartesian inertia matrix:", M_cart
00452 
00453     if True:
00454         rospy.init_node("kdl_kinematics")
00455         num_times = 20
00456         while not rospy.is_shutdown() and num_times > 0:
00457             base_link = robot.get_root()
00458             end_link = robot.links.keys()[random.randint(0, len(robot.links)-1)]
00459             print "Root link: %s; Random end link: %s" % (base_link, end_link)
00460             kdl_kin = KDLKinematics(robot, base_link, end_link)
00461             q = kdl_kin.random_joint_angles()
00462             pose = kdl_kin.forward(q)
00463             q_guess = kdl_kin.random_joint_angles()
00464             q_new = kdl_kin.inverse(pose, q_guess)
00465             if q_new is None:
00466                 print "Bad IK, trying search..."
00467                 q_search = kdl_kin.inverse_search(pose)
00468                 pose_search = kdl_kin.forward(q_search)
00469                 print "Result error:", np.linalg.norm(pose_search * pose**-1 - np.mat(np.eye(4)))
00470             num_times -= 1
00471 
00472 if __name__ == "__main__":
00473     main()


pykdl_utils
Author(s): Kelsey Hawkins / kphawkins@gatech.edu, Advisor: Prof. Charlie Kemp (Healthcare Robotics Lab at Georgia Tech)
autogenerated on Wed Nov 27 2013 11:37:37