gen_sim_arms.py
Go to the documentation of this file.
00001 #   Copyright 2013 Georgia Tech Research Corporation
00002 #
00003 #   Licensed under the Apache License, Version 2.0 (the "License");
00004 #   you may not use this file except in compliance with the License.
00005 #   You may obtain a copy of the License at
00006 #
00007 #     http://www.apache.org/licenses/LICENSE-2.0
00008 #
00009 #   Unless required by applicable law or agreed to in writing, software
00010 #   distributed under the License is distributed on an "AS IS" BASIS,
00011 #   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00012 #   See the License for the specific language governing permissions and
00013 #   limitations under the License.
00014 #
00015 #  http://healthcare-robotics.com/
00016 
00017 ## @package hrl_haptic_mpc
00018 # 
00019 # @author Jeff Hawke
00020 # @author Advait Jain
00021 # @author Marc Killpack
00022 # @version 0.1
00023 # @copyright Apache 2.0
00024 
00025 import numpy as np, math
00026 from threading import RLock
00027 import sys, copy
00028 import matplotlib.pyplot as pp
00029 
00030 import roslib; roslib.load_manifest('hrl_software_simulation_darpa_m3')
00031 
00032 import rospy
00033 import PyKDL as kdl
00034 
00035 from hrl_arm import HRLArm, HRLArmKinematics
00036 
00037 import hrl_lib.geometry as hg
00038 import hrl_lib.kdl_utils as ku
00039 import hrl_lib.viz as hv
00040 
00041 from hrl_msgs.msg import FloatArrayBare
00042 from visualization_msgs.msg import Marker
00043 from hrl_haptic_manipulation_in_clutter_msgs.msg import MechanicalImpedanceParams
00044 
00045 ## Simulation Arm client. 
00046 # @author Advait Jain
00047 class ODESimArm(HRLArm):
00048     def __init__(self, d_robot):
00049         rospy.loginfo("Loading ODESimArm")
00050         kinematics = RobotSimulatorKDL(d_robot) # KDL chain.
00051         HRLArm.__init__(self, kinematics)
00052         
00053         self.joint_names_list = ['link1', 'link2', 'link3']
00054 
00055         self.jep_pub = rospy.Publisher('/sim_arm/command/jep', FloatArrayBare)
00056         self.cep_marker_pub = rospy.Publisher('/sim_arm/viz/cep', Marker)
00057 
00058         self.impedance_pub = rospy.Publisher('/sim_arm/command/joint_impedance',
00059                                              MechanicalImpedanceParams)
00060 
00061         rospy.Subscriber('/sim_arm/joint_angles', FloatArrayBare,
00062                          self.joint_states_cb)
00063         rospy.Subscriber('/sim_arm/joint_angle_rates', FloatArrayBare,
00064                          self.joint_rates_cb)
00065         rospy.Subscriber('/sim_arm/jep', FloatArrayBare, self.jep_cb)
00066         rospy.Subscriber('/sim_arm/joint_impedance', MechanicalImpedanceParams,
00067                          self.impedance_params_cb)
00068         
00069         # Set desired joint angle - either through a delta from the current position, or as an absolute value.
00070         rospy.Subscriber ("/haptic_mpc/q_des", FloatArrayBare, self.set_ep_ros)
00071         rospy.Subscriber ("/haptic_mpc/delta_q_des", FloatArrayBare, self.set_delta_ep_ros)
00072         rospy.Subscriber ("/delta_jep_mpc_cvxgen", FloatArrayBare, self.set_delta_ep_ros)
00073 
00074 
00075         rospy.sleep(1.)
00076         rospy.loginfo("Finished loading SimpleArmManger")
00077 
00078     def jep_cb(self, msg):
00079         with self.lock:
00080             self.ep = copy.copy(msg.data)
00081 
00082     def joint_states_cb(self, data):
00083         with self.lock:
00084             self.q = copy.copy(data.data)
00085 
00086     def joint_rates_cb(self, data):
00087         with self.lock:
00088             self.qdot = copy.copy(data.data)
00089 
00090     def impedance_params_cb(self, data):
00091         with self.lock:
00092             self.kp = copy.copy(data.k_p.data)
00093             self.kd = copy.copy(data.k_d.data)
00094 
00095     def get_joint_velocities(self):
00096         with self.lock:
00097             qdot = copy.copy(self.qdot)
00098         return qdot
00099 
00100     def set_ep_ros(self, msg, duration=0.15):
00101         f = FloatArrayBare(msg.data)
00102         self.jep_pub.publish(f)
00103         self.publish_rviz_markers()
00104 
00105     def set_delta_ep_ros(self, msg, duration=0.15):
00106         delta_jep = copy.copy(msg.data)
00107         if delta_jep is None or len(delta_jep) != 3:
00108             raise RuntimeError("set_jep value is " + str(delta_jep))
00109         
00110         with self.lock:
00111           if self.ep == None:
00112             self.ep = self.get_joint_angles()
00113             
00114           jep = (np.array(self.ep) + np.array(delta_jep)).tolist()
00115           
00116           f = FloatArrayBare(jep)
00117           self.jep_pub.publish(f)
00118           self.publish_rviz_markers()
00119 
00120     def set_ep(self, jep, duration=0.15):
00121         f = FloatArrayBare(jep)
00122         self.ep = jep
00123         self.jep_pub.publish(f)
00124         self.publish_rviz_markers()
00125 
00126     def publish_rviz_markers(self):
00127         # publish the CEP marker.
00128         jep = self.get_ep()
00129         cep, r = self.kinematics.FK(jep)
00130         o = np.matrix([0.,0.,0.,1.]).T
00131         cep_marker = hv.single_marker(cep, o, 'sphere',
00132                         '/torso_lift_link', color=(0., 0., 1., 1.),
00133                         scale = (0.02, 0.02, 0.02), duration=0.)
00134 
00135         cep_marker.header.stamp = rospy.Time.now()
00136         self.cep_marker_pub.publish(cep_marker)
00137 
00138     # kp, kd - list or np array of stiffness and damping.
00139     def set_joint_impedance(self, kp, kd):
00140         im = MechanicalImpedanceParams()
00141         im.k_p.data = kp
00142         im.k_d.data = kd
00143         self.impedance_pub.publish(im)
00144 
00145 
00146 ##
00147 # KDL for kinematics etc.
00148 class RobotSimulatorKDL(HRLArmKinematics):
00149     def __init__(self, d_robot):
00150         HRLArmKinematics.__init__(self, len(d_robot.b_jt_anchor))
00151         self.arm_type = "simulated"
00152         self.d_robot = d_robot
00153         self.right_chain = self.create_right_chain()
00154         fk, ik_v, ik_p, jac = self.create_solvers(self.right_chain)
00155 
00156         self.right_fk = fk
00157         self.right_ik_v = ik_v
00158         self.right_ik_p = ik_p
00159         self.right_jac = jac
00160         self.right_tooltip = np.matrix([0.,0.,0.]).T
00161 
00162         # marc joint limits.
00163         self.min_jtlim_arr = d_robot.b_jt_limits_min
00164         self.max_jtlim_arr = d_robot.b_jt_limits_max
00165 
00166 
00167     def create_right_chain(self):
00168         height = 0.0
00169         linkage_offset_from_ground = np.matrix([0., 0., height]).T
00170         self.linkage_offset_from_ground = linkage_offset_from_ground
00171         self.n_jts = len(self.d_robot.b_jt_anchor)
00172         rospy.loginfo("number of joints is :"+str(self.n_jts))
00173 
00174         ee_location = self.d_robot.ee_location 
00175         b_jt_anchor = self.d_robot.b_jt_anchor
00176         b_jt_axis = self.d_robot.b_jt_axis
00177 
00178         ch = kdl.Chain()
00179         prev_vec = np.copy(linkage_offset_from_ground.A1)
00180         n = len(self.d_robot.b_jt_anchor)
00181 
00182         for i in xrange(n-1):
00183             if b_jt_axis[i][0] == 1 and b_jt_axis[i][1] == 0 and b_jt_axis[i][2] == 0:
00184                 kdl_jt = kdl.Joint(kdl.Joint.RotX)
00185             elif b_jt_axis[i][0] == 0 and b_jt_axis[i][1] == 1 and b_jt_axis[i][2] == 0:
00186                 kdl_jt = kdl.Joint(kdl.Joint.RotY)
00187             elif b_jt_axis[i][0] == 0 and b_jt_axis[i][1] == 0 and b_jt_axis[i][2] == 1:
00188                 kdl_jt = kdl.Joint(kdl.Joint.RotZ)
00189             else:
00190                 print "can't do off-axis joints yet!!!"
00191 
00192             np_vec = np.array(b_jt_anchor[i+1])
00193             diff_vec = np_vec-prev_vec
00194             prev_vec = np_vec
00195             kdl_vec = kdl.Vector(diff_vec[0], diff_vec[1], diff_vec[2])            
00196             ch.addSegment(kdl.Segment(kdl_jt, kdl.Frame(kdl_vec)))
00197 
00198         np_vec = np.copy(ee_location.A1)
00199         diff_vec = np_vec-prev_vec
00200 
00201         if b_jt_axis[n-1][0] == 1 and b_jt_axis[n-1][1] == 0 and b_jt_axis[n-1][2] == 0:
00202             kdl_jt = kdl.Joint(kdl.Joint.RotX)
00203         elif b_jt_axis[n-1][0] == 0 and b_jt_axis[n-1][1] == 1 and b_jt_axis[n-1][2] == 0:
00204             kdl_jt = kdl.Joint(kdl.Joint.RotY)
00205         elif b_jt_axis[n-1][0] == 0 and b_jt_axis[n-1][1] == 0 and b_jt_axis[n-1][2] == 1:
00206             kdl_jt = kdl.Joint(kdl.Joint.RotZ)
00207         else:
00208             print "can't do off-axis joints yet!!!"
00209 
00210         kdl_vec = kdl.Vector(diff_vec[0], diff_vec[1], diff_vec[2])            
00211         ch.addSegment(kdl.Segment(kdl_jt, kdl.Frame(kdl_vec)))
00212         
00213         return ch
00214 
00215     def create_solvers(self, ch):
00216          fk = kdl.ChainFkSolverPos_recursive(ch)
00217          ik_v = kdl.ChainIkSolverVel_pinv(ch)
00218          ik_p = kdl.ChainIkSolverPos_NR(ch, fk, ik_v)
00219          jac = kdl.ChainJntToJacSolver(ch)
00220          return fk, ik_v, ik_p, jac
00221 
00222     def FK_kdl(self, q, link_number):
00223         fk = self.right_fk
00224         endeffec_frame = kdl.Frame()
00225         kinematics_status = fk.JntToCart(q, endeffec_frame,
00226                                          link_number)
00227         if kinematics_status >= 0:
00228             return endeffec_frame
00229         else:
00230             rospy.loginfo('Could not compute forward kinematics.')
00231             return None
00232 
00233     ## returns point in torso lift link.
00234     def FK_vanilla(self, q, link_number=None):
00235         if link_number == None:
00236             link_number = self.n_jts
00237         link_number = min(link_number, self.n_jts)
00238 
00239         q = self.list_to_kdl(q)
00240         frame = self.FK_kdl(q, link_number)
00241         pos = frame.p
00242         pos = ku.kdl_vec_to_np(pos)
00243         pos = pos + self.linkage_offset_from_ground
00244         m = frame.M
00245         rot = ku.kdl_rot_to_np(m)
00246 
00247         return pos, rot
00248 
00249     def kdl_to_list(self, q):
00250         if q == None:
00251             return None
00252         n = self.n_jts
00253         q_list = [0] * n
00254         for i in xrange(n):
00255             q_list[i] = q[i]
00256         return q_list
00257 
00258     def list_to_kdl(self, q):
00259         if q == None:
00260             return None
00261         n = len(q)
00262         q_kdl = kdl.JntArray(n)
00263         for i in xrange(n):
00264             q_kdl[i] = q[i]
00265         return q_kdl
00266 
00267     ## compute Jacobian at point pos. 
00268     # p is in the ground coord frame.
00269     def jacobian(self, q, pos=None):
00270         if pos == None:
00271             pos = self.FK(q)[0]
00272 
00273         v_list = []
00274         w_list = []
00275 
00276         #ee, r = self.FK(q)
00277         #pos = ee
00278 
00279         for i in xrange(self.n_jts):
00280             p, rot = self.FK_vanilla(q, i)
00281             r = pos - p
00282             z_idx = self.right_chain.getSegment(i).getJoint().getType() - 1
00283             z = rot[:, z_idx]
00284             v_list.append(np.matrix(np.cross(z.A1, r.A1)).T)
00285             w_list.append(z)
00286 
00287         J = np.row_stack((np.column_stack(v_list), np.column_stack(w_list)))
00288         return J
00289 
00290     def clamp_to_joint_limits(self, q):
00291         return np.clip(q, self.min_jtlim_arr, self.max_jtlim_arr)
00292 
00293     def within_joint_limits(self, q, delta_list=None):
00294         if delta_list == None:
00295             delta_list = [0]*len(q)
00296 
00297         min_arr = self.min_jtlim_arr
00298         max_arr = self.max_jtlim_arr
00299 
00300         q_arr = np.array(q)
00301         d_arr = np.array(delta_list)
00302 
00303         return np.all((q_arr <= max_arr+d_arr, q_arr >= min_arr+d_arr))
00304 
00305     def get_joint_limits(self):
00306         return self.min_jtlim_arr, self.max_jtlim_arr
00307 
00308     # plot the arm using matplotlib.
00309     # flip_xy - x will point up and +ve y will be to the left. This is
00310     # to match how we look at the arm in rviz.
00311     def plot_arm(self, q, color, alpha, flip_xy, linewidth=2):
00312         pts = [[0.,0.,0.]]
00313         for i in range(len(q)):
00314             p,_ = self.FK(q, i+1)
00315             pts.append(p.A1.tolist())
00316 
00317         pts_2d = np.array(pts)[:,0:2]
00318         direc_list = (pts_2d[1:] - pts_2d[:-1]).tolist()
00319 
00320         for i, d in enumerate(direc_list):
00321             d_vec = np.matrix(d).T
00322             d_vec = d_vec / np.linalg.norm(d_vec)
00323             w = np.cross(d_vec.A1, np.array([0., 0., 1.])) * 0.03/2
00324             x1 = pts_2d[i,0]
00325             y1 = pts_2d[i,1]
00326             x2 = pts_2d[i+1,0]
00327             y2 = pts_2d[i+1,1]
00328 
00329             x_data = np.array([x1+w[0], x1-w[0], x2-w[0], x2+w[0], x1+w[0]])
00330             y_data = np.array([y1+w[1], y1-w[1], y2-w[1], y2+w[1], y1+w[1]])
00331 
00332             if flip_xy:
00333                 tmp = y_data
00334                 y_data = x_data
00335                 x_data = -tmp
00336 
00337             pp.plot(x_data, y_data, '-', alpha=alpha, color=color,
00338                     linewidth=linewidth)
00339 
00340 
00341 if __name__ == '__main__':
00342     rospy.init_node('ode_arms_test')
00343     import hrl_common_code_darpa_m3.robot_config.six_link_planar as d_robot
00344     ode_arm = ODESimArm(d_robot)
00345 
00346     # test_jep = np.radians([30., 20., 45.])
00347     test_jep = np.radians(np.zeros(ode_arm.kinematics.n_jts))
00348     # test_jep = np.radians([90]*6)    
00349     # test_jep = np.radians([0., 0., 0.])
00350     p, _ = ode_arm.kinematics.FK(test_jep, ode_arm.kinematics.n_jts)
00351     print 'p:', p.A1
00352 
00353     ode_arm.set_ep(test_jep)
00354 
00355 
00356 


hrl_haptic_mpc
Author(s): Jeff Hawke, Phillip Grice, Marc Killpack, Advait Jain. Advisor and Co-author: Prof. Charlie Kemp. Healthcare Robotics Lab, Georgia Tech
autogenerated on Wed Nov 27 2013 12:27:09