skeleton_sender.py
Go to the documentation of this file.
00001 #!/usr/bin/python
00002 
00003 __author__ = 'Igor Zubrycki'
00004 
00005 """ For backwards compatibility with the old driver files
00006                 Will be DELETED in the future               """
00007 
00008 import rospy
00009 import leap_interface
00010 import tf
00011 import sys
00012 import Leap
00013 import math
00014 import roslib
00015 import rospy
00016 from std_msgs.msg import String
00017 from std_msgs.msg import Float64
00018 import std_msgs.msg
00019 import sensor_msgs.msg
00020 import actionlib_msgs.msg
00021 import trajectory_msgs.msg
00022 import collections
00023 import scipy.signal as signal
00024 import geometry_msgs.msg
00025 import PyKDL
00026 
00027 finger_names=["thumb","index","middle","ring","pinky"]
00028 bones_names=["metacarpal","proximal","intermediate","distal"]
00029 
00030 def make_kdl_frame(leap_basis_matrix,leap_position_vector,is_left=False):
00031     # Makes kdl frame from Leap Motion matrix and vector formats
00032     
00033     if is_left:
00034        basis=([-el for el in leap_basis_matrix.x_basis.to_float_array()]+
00035        leap_basis_matrix.y_basis.to_float_array()+
00036        leap_basis_matrix.z_basis.to_float_array())
00037        
00038     else:
00039        basis=leap_basis_matrix.to_array_3x3() 
00040     rotation_mat=PyKDL.Rotation(*basis).Inverse()
00041     # rotation_mat=PyKDL.Rotation(*[1,0,0,0,1,0,0,0,1])#.Inverse()
00042     placement=PyKDL.Vector(*leap_position_vector.to_float_array())/1000.0 #to m
00043     return PyKDL.Frame(rotation_mat,placement)
00044     
00045 def relative_frame(frame_A,frame_B):
00046 
00047     return (frame_A.Inverse())*frame_B
00048 
00049 
00050 hand_ground_tf=PyKDL.Frame(PyKDL.Rotation.EulerZYX(0, 0, math.pi/2.0),PyKDL.Vector(0,0,0))
00051 
00052 def make_tf_dict(hand,hand_name):
00053     
00054     hand_dict={}
00055     # hand_ground_tf=
00056     hand_dict["hand_ground"]=["ground",hand_ground_tf]
00057     
00058             
00059     hand_tf=make_kdl_frame(hand.basis,hand.palm_position,hand.is_left)
00060     # hand_tf=make_kdl_frame(hand.basis,hand.palm_position)
00061     hand_dict[hand_name]=["hand_ground",hand_tf]
00062     for finger in hand.fingers:
00063         finger_name=hand_name+"_"+finger_names[finger.type()]
00064         
00065         prev_bone_name=hand_name
00066         for num in range(0,4):
00067             
00068             bone=finger.bone(num)
00069 
00070             bone_absolute=make_kdl_frame(bone.basis,bone.prev_joint,hand.is_left)
00071             if num==0:
00072                 bone_tf=relative_frame(hand_tf,bone_absolute)
00073             else:
00074                 bone_tf=relative_frame(prev_bone_absolute,bone_absolute)
00075 
00076             bone_name=finger_name+"_"+bones_names[num]
00077             hand_dict[bone_name]=[prev_bone_name,bone_tf]
00078             
00079             prev_bone_name=bone_name
00080             prev_bone_absolute=bone_absolute
00081             
00082         tip=PyKDL.Frame(PyKDL.Rotation(1,0,0, 0,1,0, 0,0,1),PyKDL.Vector(0,0,-bone.length/1000.0))
00083         hand_dict[finger_name+"_tip"]=[prev_bone_name,tip]    
00084     return hand_dict    
00085      # now sending to ROS       
00086         
00087 
00088 def broadcast_hand(hand,hand_name,timenow):
00089     hand_dict=make_tf_dict(hand,hand_name)
00090     br = tf.TransformBroadcaster()
00091 
00092 
00093     for tf_name,tf_array in hand_dict.items():
00094         tf_matrix=tf_array[1]
00095         tf_prev_name=tf_array[0]
00096         br.sendTransform(tf_matrix.p,tf_matrix.M.GetQuaternion(),timenow,tf_name,tf_prev_name)
00097 
00098 def sender():
00099     li = leap_interface.Runner()
00100     li.setDaemon(True)
00101     li.start()
00102     # pub     = rospy.Publisher('leapmotion/raw',leap)
00103     # pub_ros   = rospy.Publisher('leapmotion/data',leapros)
00104     rospy.init_node('leap_skeleton_pub')
00105 
00106     
00107     while not rospy.is_shutdown():
00108         timenow=rospy.Time.now()
00109         if li.listener.left_hand:
00110             broadcast_hand(li.listener.left_hand,"left_hand",timenow)
00111         if li.listener.right_hand:
00112             broadcast_hand(li.listener.right_hand,"right_hand",timenow)
00113 
00114         # save some CPU time, circa 100Hz publishing.
00115         rospy.sleep(0.01)
00116 
00117 
00118 if __name__ == '__main__':
00119     try:
00120         sender()
00121     except rospy.ROSInterruptException:
00122         pass


leap_motion
Author(s): Florian Lier , Mirza Shah , Isaac IY Saito
autogenerated on Sat Jun 8 2019 18:47:25