00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
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
00053
00054 class JointKinematics(KDLKinematics):
00055
00056
00057
00058
00059
00060
00061
00062
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
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
00091
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
00107
00108
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
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
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
00136
00137
00138
00139
00140
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
00150
00151
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
00161
00162
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
00172
00173
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
00183
00184
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
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()