joint_kinematics.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 #
00003 # Kinematics class which subscribes to the /joint_states topic, providing utility
00004 # methods for it on top of those provided by KDLKinematics.
00005 #
00006 # Copyright (c) 2012, Georgia Tech Research Corporation
00007 # All rights reserved.
00008 # 
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions are met:
00011 #     * Redistributions of source code must retain the above copyright
00012 #       notice, this list of conditions and the following disclaimer.
00013 #     * Redistributions in binary form must reproduce the above copyright
00014 #       notice, this list of conditions and the following disclaimer in the
00015 #       documentation and/or other materials provided with the distribution.
00016 #     * Neither the name of the Georgia Tech Research Corporation nor the
00017 #       names of its contributors may be used to endorse or promote products
00018 #       derived from this software without specific prior written permission.
00019 # 
00020 # THIS SOFTWARE IS PROVIDED BY GEORGIA TECH RESEARCH CORPORATION ''AS IS'' AND
00021 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00022 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00023 # DISCLAIMED. IN NO EVENT SHALL GEORGIA TECH BE LIABLE FOR ANY DIRECT, INDIRECT,
00024 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00025 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00026 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00027 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00028 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00029 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00030 #
00031 # Author: Kelsey Hawkins
00032 
00033 import numpy as np
00034 
00035 import roslib
00036 roslib.load_manifest('pykdl_utils')
00037 
00038 import rospy
00039 from sensor_msgs.msg import JointState
00040 
00041 from urdf_parser_py.urdf import URDF
00042 from pykdl_utils.kdl_kinematics import KDLKinematics
00043 
00044 def create_joint_kin(base_link, end_link, urdf_filename=None, timeout=1.):
00045     if urdf_filename is None:
00046         robot = URDF.load_from_parameter_server(verbose=False)
00047     else:
00048         robot = URDF.load_xml_file(urdf_filename, verbose=False)
00049     return JointKinematics(robot, base_link, end_link, timeout=timeout)
00050 
00051 ##
00052 # Kinematics class which subscribes to the /joint_states topic, recording the current
00053 # joint states for the kinematic chain designated.
00054 class JointKinematics(KDLKinematics):
00055     ##
00056     # Constructor
00057     # @param urdf URDF object of robot.
00058     # @param base_link Name of the root link of the kinematic chain.
00059     # @param end_link Name of the end link of the kinematic chain.
00060     # @param kdl_tree Optional KDL.Tree object to use. If None, one will be generated
00061     #                          from the URDF.
00062     # @param timeout Time in seconds to wait for the /joint_states topic.
00063     def __init__(self, urdf, base_link, end_link, kdl_tree=None, timeout=1.):
00064         super(JointKinematics, self).__init__(urdf, base_link, end_link, kdl_tree)
00065         self._joint_angles = None
00066         self._joint_velocities = None
00067         self._joint_efforts = None
00068         self._joint_state_inds = None
00069 
00070         rospy.Subscriber('/joint_states', JointState, self._joint_state_cb)
00071 
00072         if timeout > 0:
00073             self.wait_for_joint_angles(timeout)
00074 
00075     ##
00076     # Joint angles listener callback
00077     def _joint_state_cb(self, msg):
00078         if self._joint_state_inds is None:
00079             joint_names_list = self.get_joint_names()
00080             self._joint_state_inds = [msg.name.index(joint_name) for 
00081                                      joint_name in joint_names_list]
00082         if len(msg.position) == len(self._joint_state_inds):
00083             self._joint_angles = [msg.position[i] for i in self._joint_state_inds]
00084         if len(msg.velocity) == len(self._joint_state_inds):
00085             self._joint_velocities = [msg.velocity[i] for i in self._joint_state_inds]
00086         if len(msg.effort) == len(self._joint_state_inds):
00087             self._joint_efforts = [msg.effort[i] for i in self._joint_state_inds]
00088 
00089     ##
00090     # Wait until we have found the current joint angles.
00091     # @param timeout Time at which we break if we haven't recieved the angles.
00092     def wait_for_joint_angles(self, timeout=1.):
00093         if timeout <= 0:
00094             return self._joint_angles is not None
00095         start_time = rospy.get_time()
00096         r = rospy.Rate(100)
00097         while not rospy.is_shutdown() and rospy.get_time() - start_time < timeout:
00098             if self._joint_angles is not None:
00099                 return True
00100             r.sleep()
00101         if not rospy.is_shutdown():
00102             rospy.logwarn("[joint_state_kdl_kin] Cannot read joint angles, timing out.")
00103         return False
00104 
00105     ##
00106     # Returns the current joint angle positions
00107     # @param wrapped If False returns the raw encoded positions, if True returns
00108     #                the angles with the forearm and wrist roll in the range -pi to pi
00109     def get_joint_angles(self, wrapped=False):
00110         if self._joint_angles is None:
00111             rospy.logwarn("[joint_state_kdl_kin] Joint angles haven't been filled yet.")
00112             return None
00113         if wrapped:
00114             return self.wrap_angles(self._joint_angles)
00115         else:
00116             return np.array(self._joint_angles).copy()
00117 
00118     ##
00119     # Returns the current joint velocities
00120     def get_joint_velocities(self):
00121         if self._joint_velocities is None:
00122             rospy.logwarn("[joint_state_kdl_kin] Joint velocities haven't been filled yet.")
00123             return None
00124         return np.array(self._joint_velocities).copy()
00125 
00126     ##
00127     # Returns the current joint efforts
00128     def get_joint_efforts(self):
00129         if self._joint_efforts is None:
00130             rospy.logwarn("[joint_state_kdl_kin] Joint efforts haven't been filled yet.")
00131             return None
00132         return np.array(self._joint_efforts).copy()
00133 
00134     ##
00135     # Perform forward kinematics on the current joint angles.
00136     # @param q List of joint angles for the full kinematic chain. 
00137     #          If None, the current joint angles are used.
00138     # @param end_link Name of the link the pose should be obtained for.
00139     # @param base_link Name of the root link frame the end_link should be found in.
00140     # @return 4x4 numpy.mat homogeneous transformation or None if the joint angles are not filled.
00141     def forward(self, q=None, end_link=None, base_link=None):
00142         if q is None:
00143             q = self.get_joint_angles()
00144             if q is None:
00145                 return None
00146         return super(JointKinematics, self).forward(q, end_link, base_link)
00147 
00148     ##
00149     # Returns the Jacobian matrix at the end_link from the current joint angles.
00150     # @param q List of joint angles. If None, the current joint angles are used.
00151     # @return 6xN np.mat Jacobian or None if the joint angles are not filled.
00152     def jacobian(self, q=None):
00153         if q is None:
00154             q = self.get_joint_angles()
00155             if q is None:
00156                 return None
00157         return super(JointKinematics, self).jacobian(q)
00158 
00159     ##
00160     # Returns the joint space mass matrix at the end_link for the given joint angles.
00161     # @param q List of joint angles.
00162     # @return NxN np.mat Inertia matrix or None if the joint angles are not filled.
00163     def inertia(self, q=None):
00164         if q is None:
00165             q = self.get_joint_angles()
00166             if q is None:
00167                 return None
00168         return super(JointKinematics, self).inertia(q)
00169 
00170     ##
00171     # Returns the cartesian space mass matrix at the end_link for the given joint angles.
00172     # @param q List of joint angles.
00173     # @return 6x6 np.mat Cartesian inertia matrix or None if the joint angles are not filled.
00174     def cart_inertia(self, q=None):
00175         if q is None:
00176             q = self.get_joint_angles()
00177             if q is None:
00178                 return None
00179         return super(JointKinematics, self).cart_inertia(q)
00180 
00181     ##
00182     # Returns joint angles for continuous joints to a range [0, 2*PI)
00183     # @param q List of joint angles.
00184     # @return np.array of wrapped joint angles.
00185     def wrap_angles(self, q):
00186         contins = self.joint_types == 'continuous'
00187         return np.where(contins, np.mod(q, 2 * np.pi), q)
00188 
00189     ##
00190     # Returns the current effective end effector force.
00191     def end_effector_force(self):
00192         J = self.jacobian()
00193         tau = self.get_joint_efforts()
00194         if J is None or tau is None:
00195             return None
00196         f, _, _, _ = np.linalg.lstsq(J.T, tau)
00197         return f
00198 
00199 def main():
00200     rospy.init_node("joint_kinematics")
00201     import sys
00202     def usage():
00203         print("Tests for kdl_parser:\n")
00204         print("kdl_parser <urdf file>")
00205         print("\tLoad the URDF from file.")
00206         print("kdl_parser")
00207         print("\tLoad the URDF from the parameter server.")
00208         sys.exit(1)
00209 
00210     if len(sys.argv) > 2:
00211         usage()
00212     if len(sys.argv) == 2 and (sys.argv[1] == "-h" or sys.argv[1] == "--help"):
00213         usage()
00214     if (len(sys.argv) == 1):
00215         robot = URDF.load_from_parameter_server(verbose=False)
00216     else:
00217         robot = URDF.load_xml_file(sys.argv[1], verbose=False)
00218 
00219     if True:
00220         import random
00221         base_link = robot.get_root()
00222         end_link = robot.links.keys()[random.randint(0, len(robot.links)-1)]
00223         print "Root link: %s; Random end link: %s" % (base_link, end_link)
00224         js_kin = JointKinematics(robot, base_link, end_link)
00225         print "Joint angles:", js_kin.get_joint_angles()
00226         print "Joint angles (wrapped):", js_kin.get_joint_angles(True)
00227         print "Joint velocities:", js_kin.get_joint_velocities()
00228         print "Joint efforts:", js_kin.get_joint_efforts()
00229         print "Jacobian:", js_kin.jacobian()
00230         kdl_pose = js_kin.forward()
00231         print "FK:", kdl_pose
00232         print "End effector force:", js_kin.end_effector_force()
00233 
00234         if True:
00235             import tf 
00236             from hrl_geom.pose_converter import PoseConv
00237             tf_list = tf.TransformListener()
00238             rospy.sleep(1)
00239             t = tf_list.getLatestCommonTime(base_link, end_link)
00240             tf_pose = PoseConv.to_homo_mat(tf_list.lookupTransform(base_link, end_link, t))
00241             print "Error with TF:", np.linalg.norm(kdl_pose - tf_pose)
00242 
00243 if __name__ == "__main__":
00244     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