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 PyKDL as kdl
00035 import rospy
00036 
00037 from sensor_msgs.msg import JointState
00038 import hrl_geom.transformations as trans
00039 from hrl_geom.pose_converter import PoseConv
00040 from kdl_parser import kdl_tree_from_urdf_model
00041 from urdf_parser_py.urdf import Robot
00042 
00043 def create_kdl_kin(base_link, end_link, urdf_filename=None, description_param="robot_description"):
00044     if urdf_filename is None:
00045         robot = Robot.from_parameter_server(key=description_param)
00046     else:
00047         f = file(urdf_filename, 'r')
00048         robot = Robot.from_xml_string(f.read())
00049         f.close()
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.joint_map[jnt_name]
00084             if jnt.limit is not None:
00085                 self.joint_limits_lower.append(jnt.limit.lower)
00086                 self.joint_limits_upper.append(jnt.limit.upper)
00087             else:
00088                 self.joint_limits_lower.append(None)
00089                 self.joint_limits_upper.append(None)
00090             if jnt.safety_controller is not None:
00091                 self.joint_safety_lower.append(jnt.safety_controller.soft_lower_limit)#.lower)
00092                 self.joint_safety_upper.append(jnt.safety_controller.soft_upper_limit)#.upper)
00093             elif jnt.limit is not None:
00094                 self.joint_safety_lower.append(jnt.limit.lower)
00095                 self.joint_safety_upper.append(jnt.limit.upper)
00096             else:
00097                 self.joint_safety_lower.append(None)
00098                 self.joint_safety_upper.append(None)
00099             self.joint_types.append(jnt.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     def extract_joint_state(self, js, joint_names=None):
00122         if joint_names is None:
00123             joint_names = self.get_joint_names()
00124         q   = np.zeros(len(joint_names))
00125         qd  = np.zeros(len(joint_names))
00126         eff = np.zeros(len(joint_names))
00127         for i, joint_name in enumerate(joint_names):
00128             js_idx = js.name.index(joint_name)
00129             if js_idx < len(js.position) and q is not None:
00130                 q[i]   = js.position[js_idx]
00131             else:
00132                 q = None
00133             if js_idx < len(js.velocity) and qd is not None:
00134                 qd[i]  = js.velocity[js_idx]
00135             else:
00136                 qd = None
00137             if js_idx < len(js.effort) and eff is not None:
00138                 eff[i] = js.effort[js_idx]
00139             else:
00140                 eff = None
00141         return q, qd, eff
00142 
00143     ##
00144     # @return List of link names in the kinematic chain.
00145     def get_link_names(self, joints=False, fixed=True):
00146         return self.urdf.get_chain(self.base_link, self.end_link, joints, fixed)
00147 
00148     ##
00149     # @return List of joint names in the kinematic chain.
00150     def get_joint_names(self, links=False, fixed=False):
00151         return self.urdf.get_chain(self.base_link, self.end_link,
00152                                    links=links, fixed=fixed)
00153 
00154     def get_joint_limits(self):
00155         return self.joint_limits_lower, self.joint_limits_upper
00156 
00157     def FK(self, q, link_number=None):
00158         if link_number is not None:
00159             end_link = self.get_link_names(fixed=False)[link_number]
00160         else:
00161             end_link = None
00162         homo_mat = self.forward(q, end_link)
00163         pos, rot = PoseConv.to_pos_rot(homo_mat)
00164         return pos, rot
00165 
00166 
00167     ##
00168     # Forward kinematics on the given joint angles, returning the location of the
00169     # end_link in the base_link's frame.
00170     # @param q List of joint angles for the full kinematic chain.
00171     # @param end_link Name of the link the pose should be obtained for.
00172     # @param base_link Name of the root link frame the end_link should be found in.
00173     # @return 4x4 numpy.mat homogeneous transformation
00174     def forward(self, q, end_link=None, base_link=None):
00175         link_names = self.get_link_names()
00176         if end_link is None:
00177             end_link = self.chain.getNrOfSegments()
00178         else:
00179             end_link = end_link.split("/")[-1]
00180             if end_link in link_names:
00181                 end_link = link_names.index(end_link)
00182             else:
00183                 print "Target segment %s not in KDL chain" % end_link
00184                 return None
00185         if base_link is None:
00186             base_link = 0
00187         else:
00188             base_link = base_link.split("/")[-1]
00189             if base_link in link_names:
00190                 base_link = link_names.index(base_link)
00191             else:
00192                 print "Base segment %s not in KDL chain" % base_link
00193                 return None
00194         base_trans = self._do_kdl_fk(q, base_link)
00195         if base_trans is None:
00196             print "FK KDL failure on base transformation."
00197         end_trans = self._do_kdl_fk(q, end_link)
00198         if end_trans is None:
00199             print "FK KDL failure on end transformation."
00200         return base_trans**-1 * end_trans
00201 
00202     def _do_kdl_fk(self, q, link_number):
00203         endeffec_frame = kdl.Frame()
00204         kinematics_status = self._fk_kdl.JntToCart(joint_list_to_kdl(q),
00205                                                    endeffec_frame,
00206                                                    link_number)
00207         if kinematics_status >= 0:
00208             p = endeffec_frame.p
00209             M = endeffec_frame.M
00210             return np.mat([[M[0,0], M[0,1], M[0,2], p.x()],
00211                            [M[1,0], M[1,1], M[1,2], p.y()],
00212                            [M[2,0], M[2,1], M[2,2], p.z()],
00213                            [     0,      0,      0,     1]])
00214         else:
00215             return None
00216 
00217     ##
00218     # Inverse kinematics for a given pose, returning the joint angles required
00219     # to obtain the target pose.
00220     # @param pose Pose-like object represeting the target pose of the end effector.
00221     # @param q_guess List of joint angles to seed the IK search.
00222     # @param min_joints List of joint angles to lower bound the angles on the IK search.
00223     #                   If None, the safety limits are used.
00224     # @param max_joints List of joint angles to upper bound the angles on the IK search.
00225     #                   If None, the safety limits are used.
00226     # @return np.array of joint angles needed to reach the pose or None if no solution was found.
00227     def inverse(self, pose, q_guess=None, min_joints=None, max_joints=None):
00228         pos, rot = PoseConv.to_pos_rot(pose)
00229         pos_kdl = kdl.Vector(pos[0,0], pos[1,0], pos[2,0])
00230         rot_kdl = kdl.Rotation(rot[0,0], rot[0,1], rot[0,2],
00231                                rot[1,0], rot[1,1], rot[1,2],
00232                                rot[2,0], rot[2,1], rot[2,2])
00233         frame_kdl = kdl.Frame(rot_kdl, pos_kdl)
00234         if min_joints is None:
00235             min_joints = self.joint_safety_lower
00236         if max_joints is None:
00237             max_joints = self.joint_safety_upper
00238         mins_kdl = joint_list_to_kdl(min_joints)
00239         maxs_kdl = joint_list_to_kdl(max_joints)
00240         ik_p_kdl = kdl.ChainIkSolverPos_NR_JL(self.chain, mins_kdl, maxs_kdl,
00241                                               self._fk_kdl, self._ik_v_kdl)
00242 
00243         if q_guess == None:
00244             # use the midpoint of the joint limits as the guess
00245             lower_lim = np.where(np.isfinite(min_joints), min_joints, 0.)
00246             upper_lim = np.where(np.isfinite(max_joints), max_joints, 0.)
00247             q_guess = (lower_lim + upper_lim) / 2.0
00248             q_guess = np.where(np.isnan(q_guess), [0.]*len(q_guess), q_guess)
00249 
00250         q_kdl = kdl.JntArray(self.num_joints)
00251         q_guess_kdl = joint_list_to_kdl(q_guess)
00252         if ik_p_kdl.CartToJnt(q_guess_kdl, frame_kdl, q_kdl) >= 0:
00253             return np.array(joint_kdl_to_list(q_kdl))
00254         else:
00255             return None
00256 
00257     ##
00258     # Repeats IK for different sets of random initial angles until a solution is found
00259     # or the call times out.
00260     # @param pose Pose-like object represeting the target pose of the end effector.
00261     # @param timeout Time in seconds to look for a solution.
00262     # @return np.array of joint angles needed to reach the pose or None if no solution was found.
00263     def inverse_search(self, pose, timeout=1.):
00264         st_time = rospy.get_time()
00265         while not rospy.is_shutdown() and rospy.get_time() - st_time < timeout:
00266             q_init = self.random_joint_angles()
00267             q_ik = self.inverse(pose, q_init)
00268             if q_ik is not None:
00269                 return q_ik
00270         return None
00271 
00272     ##
00273     # Returns the Jacobian matrix at the end_link for the given joint angles.
00274     # @param q List of joint angles.
00275     # @return 6xN np.mat Jacobian
00276     # @param pos Point in base frame where the jacobian is acting on.
00277     #            If None, we assume the end_link
00278     def jacobian(self, q, pos=None):
00279         j_kdl = kdl.Jacobian(self.num_joints)
00280         q_kdl = joint_list_to_kdl(q)
00281         self._jac_kdl.JntToJac(q_kdl, j_kdl)
00282         if pos is not None:
00283             ee_pos = self.forward(q)[:3,3]
00284             pos_kdl = kdl.Vector(pos[0]-ee_pos[0], pos[1]-ee_pos[1],
00285                                   pos[2]-ee_pos[2])
00286             j_kdl.changeRefPoint(pos_kdl)
00287         return kdl_to_mat(j_kdl)
00288 
00289     ##
00290     # Returns the joint space mass matrix at the end_link for the given joint angles.
00291     # @param q List of joint angles.
00292     # @return NxN np.mat Inertia matrix
00293     def inertia(self, q):
00294         h_kdl = kdl.JntSpaceInertiaMatrix(self.num_joints)
00295         self._dyn_kdl.JntToMass(joint_list_to_kdl(q), h_kdl)
00296         return kdl_to_mat(h_kdl)
00297 
00298     ##
00299     # Returns the cartesian space mass matrix at the end_link for the given joint angles.
00300     # @param q List of joint angles.
00301     # @return 6x6 np.mat Cartesian inertia matrix
00302     def cart_inertia(self, q):
00303         H = self.inertia(q)
00304         J = self.jacobian(q)
00305         return np.linalg.inv(J * np.linalg.inv(H) * J.T)
00306 
00307     ##
00308     # Tests to see if the given joint angles are in the joint limits.
00309     # @param List of joint angles.
00310     # @return True if joint angles in joint limits.
00311     def joints_in_limits(self, q):
00312         lower_lim = self.joint_limits_lower
00313         upper_lim = self.joint_limits_upper
00314         return np.all([q >= lower_lim, q <= upper_lim], 0)
00315 
00316     ##
00317     # Tests to see if the given joint angles are in the joint safety limits.
00318     # @param List of joint angles.
00319     # @return True if joint angles in joint safety limits.
00320     def joints_in_safe_limits(self, q):
00321         lower_lim = self.joint_safety_lower
00322         upper_lim = self.joint_safety_upper
00323         return np.all([q >= lower_lim, q <= upper_lim], 0)
00324 
00325     ##
00326     # Clips joint angles to the safety limits.
00327     # @param List of joint angles.
00328     # @return np.array list of clipped joint angles.
00329     def clip_joints_safe(self, q):
00330         lower_lim = self.joint_safety_lower
00331         upper_lim = self.joint_safety_upper
00332         return np.clip(q, lower_lim, upper_lim)
00333 
00334     ##
00335     # Returns a set of random joint angles distributed uniformly in the safety limits.
00336     # @return np.array list of random joint angles.
00337     def random_joint_angles(self):
00338         lower_lim = self.joint_safety_lower
00339         upper_lim = self.joint_safety_upper
00340         lower_lim = np.where(np.isfinite(lower_lim), lower_lim, -np.pi)
00341         upper_lim = np.where(np.isfinite(upper_lim), upper_lim, np.pi)
00342         zip_lims = zip(lower_lim, upper_lim)
00343         return np.array([np.random.uniform(min_lim, max_lim) for min_lim, max_lim in zip_lims])
00344 
00345     ##
00346     # Returns a difference between the two sets of joint angles while insuring
00347     # that the shortest angle is returned for the continuous joints.
00348     # @param q1 List of joint angles.
00349     # @param q2 List of joint angles.
00350     # @return np.array of wrapped joint angles for retval = q1 - q2
00351     def difference_joints(self, q1, q2):
00352         diff = np.array(q1) - np.array(q2)
00353         diff_mod = np.mod(diff, 2 * np.pi)
00354         diff_alt = diff_mod - 2 * np.pi
00355         for i, continuous in enumerate(self.joint_types == 'continuous'):
00356             if continuous:
00357                 if diff_mod[i] < -diff_alt[i]:
00358                     diff[i] = diff_mod[i]
00359                 else:
00360                     diff[i] = diff_alt[i]
00361         return diff
00362 
00363     ##
00364     # Performs an IK search while trying to balance the demands of reaching the goal,
00365     # maintaining a posture, and prioritizing rotation or position.
00366     def inverse_biased(self, pose, q_init, q_bias, q_bias_weights, rot_weight=1.,
00367                        bias_vel=0.01, num_iter=100):
00368         # This code is potentially volatile
00369         q_out = np.mat(self.inverse_search(pose)).T
00370         for i in range(num_iter):
00371             pos_fk, rot_fk = PoseConv.to_pos_rot(self.forward(q_out))
00372             delta_twist = np.mat(np.zeros((6, 1)))
00373             pos_delta = pos - pos_fk
00374             delta_twist[:3,0] = pos_delta
00375             rot_delta = np.mat(np.eye(4))
00376             rot_delta[:3,:3] = rot * rot_fk.T
00377             rot_delta_angles = np.mat(trans.euler_from_matrix(rot_delta)).T
00378             delta_twist[3:6,0] = rot_delta_angles
00379             J = self.jacobian(q_out)
00380             J[3:6,:] *= np.sqrt(rot_weight)
00381             delta_twist[3:6,0] *= np.sqrt(rot_weight)
00382             J_tinv = np.linalg.inv(J.T * J + np.diag(q_bias_weights) * np.eye(len(q_init))) * J.T
00383             q_bias_diff = q_bias - q_out
00384             q_bias_diff_normed = q_bias_diff * bias_vel / np.linalg.norm(q_bias_diff)
00385             delta_q = q_bias_diff_normed + J_tinv * (delta_twist - J * q_bias_diff_normed)
00386             q_out += delta_q
00387             q_out = np.mat(self.clip_joints_safe(q_out.T.A[0])).T
00388         return q_out
00389 
00390     ##
00391     # inverse_biased with random restarts.
00392     def inverse_biased_search(self, pos, rot, q_bias, q_bias_weights, rot_weight=1.,
00393                               bias_vel=0.01, num_iter=100, num_search=20):
00394         # This code is potentially volatile
00395         q_sol_min = []
00396         min_val = 1000000.
00397         for i in range(num_search):
00398             q_init = self.random_joint_angles()
00399             q_sol = self.inverse_biased(pos, rot, q_init, q_bias, q_bias_weights, rot_weight=1.,
00400                                         bias_vel=bias_vel, num_iter=num_iter)
00401             cur_val = np.linalg.norm(np.diag(q_bias_weights) * (q_sol - q_bias))
00402             if cur_val < min_val:
00403                 min_val = cur_val
00404                 q_sol_min = q_sol
00405         return q_sol_min
00406 
00407 
00408 def kdl_to_mat(m):
00409     mat =  np.mat(np.zeros((m.rows(), m.columns())))
00410     for i in range(m.rows()):
00411         for j in range(m.columns()):
00412             mat[i,j] = m[i,j]
00413     return mat
00414 
00415 def joint_kdl_to_list(q):
00416     if q == None:
00417         return None
00418     return [q[i] for i in range(q.rows())]
00419 
00420 def joint_list_to_kdl(q):
00421     if q is None:
00422         return None
00423     if type(q) == np.matrix and q.shape[1] == 0:
00424         q = q.T.tolist()[0]
00425     q_kdl = kdl.JntArray(len(q))
00426     for i, q_i in enumerate(q):
00427         q_kdl[i] = q_i
00428     return q_kdl
00429 
00430 def main():
00431     import sys
00432     def usage():
00433         print("Tests for kdl_parser:\n")
00434         print("kdl_parser <urdf file>")
00435         print("\tLoad the URDF from file.")
00436         print("kdl_parser")
00437         print("\tLoad the URDF from the parameter server.")
00438         sys.exit(1)
00439 
00440     if len(sys.argv) > 2:
00441         usage()
00442     if len(sys.argv) == 2 and (sys.argv[1] == "-h" or sys.argv[1] == "--help"):
00443         usage()
00444     if (len(sys.argv) == 1):
00445         robot = Robot.from_parameter_server()
00446     else:
00447         f = file(sys.argv[1], 'r')
00448         robot = Robot.from_xml_string(f.read())
00449         f.close()
00450 
00451     if True:
00452         import random
00453         base_link = robot.get_root()
00454         end_link = robot.link_map.keys()[random.randint(0, len(robot.link_map)-1)]
00455         print "Root link: %s; Random end link: %s" % (base_link, end_link)
00456         kdl_kin = KDLKinematics(robot, base_link, end_link)
00457         q = kdl_kin.random_joint_angles()
00458         print "Random angles:", q
00459         pose = kdl_kin.forward(q)
00460         print "FK:", pose
00461         q_new = kdl_kin.inverse(pose)
00462         print "IK (not necessarily the same):", q_new
00463         if q_new is not None:
00464             pose_new = kdl_kin.forward(q_new)
00465             print "FK on IK:", pose_new
00466             print "Error:", np.linalg.norm(pose_new * pose**-1 - np.mat(np.eye(4)))
00467         else:
00468             print "IK failure"
00469         J = kdl_kin.jacobian(q)
00470         print "Jacobian:", J
00471         M = kdl_kin.inertia(q)
00472         print "Inertia matrix:", M
00473         if False:
00474             M_cart = kdl_kin.cart_inertia(q)
00475             print "Cartesian inertia matrix:", M_cart
00476 
00477     if True:
00478         rospy.init_node("kdl_kinematics")
00479         num_times = 20
00480         while not rospy.is_shutdown() and num_times > 0:
00481             base_link = robot.get_root()
00482             end_link = robot.link_map.keys()[random.randint(0, len(robot.link_map)-1)]
00483             print "Root link: %s; Random end link: %s" % (base_link, end_link)
00484             kdl_kin = KDLKinematics(robot, base_link, end_link)
00485             q = kdl_kin.random_joint_angles()
00486             pose = kdl_kin.forward(q)
00487             q_guess = kdl_kin.random_joint_angles()
00488             q_new = kdl_kin.inverse(pose, q_guess)
00489             if q_new is None:
00490                 print "Bad IK, trying search..."
00491                 q_search = kdl_kin.inverse_search(pose)
00492                 pose_search = kdl_kin.forward(q_search)
00493                 print "Result error:", np.linalg.norm(pose_search * pose**-1 - np.mat(np.eye(4)))
00494             num_times -= 1
00495 
00496 if __name__ == "__main__":
00497     main()


pykdl_utils
Author(s): Kelsey Hawkins
autogenerated on Fri Aug 28 2015 11:05:34