3 __author__ =
'Igor Zubrycki' 5 """ For backwards compatibility with the old driver files 6 Will be DELETED in the future """ 16 from std_msgs.msg
import String
17 from std_msgs.msg
import Float64
19 import sensor_msgs.msg
20 import actionlib_msgs.msg
21 import trajectory_msgs.msg
23 import scipy.signal
as signal
24 import geometry_msgs.msg
27 finger_names=[
"thumb",
"index",
"middle",
"ring",
"pinky"]
28 bones_names=[
"metacarpal",
"proximal",
"intermediate",
"distal"]
34 basis=([-el
for el
in leap_basis_matrix.x_basis.to_float_array()]+
35 leap_basis_matrix.y_basis.to_float_array()+
36 leap_basis_matrix.z_basis.to_float_array())
39 basis=leap_basis_matrix.to_array_3x3()
40 rotation_mat=PyKDL.Rotation(*basis).Inverse()
42 placement=PyKDL.Vector(*leap_position_vector.to_float_array())/1000.0
43 return PyKDL.Frame(rotation_mat,placement)
47 return (frame_A.Inverse())*frame_B
50 hand_ground_tf=PyKDL.Frame(PyKDL.Rotation.EulerZYX(0, 0, math.pi/2.0),PyKDL.Vector(0,0,0))
56 hand_dict[
"hand_ground"]=[
"ground",hand_ground_tf]
61 hand_dict[hand_name]=[
"hand_ground",hand_tf]
62 for finger
in hand.fingers:
63 finger_name=hand_name+
"_"+finger_names[finger.type]
65 prev_bone_name=hand_name
66 for num
in range(0,4):
70 bone_absolute=
make_kdl_frame(bone.basis,bone.prev_joint,hand.is_left)
76 bone_name=finger_name+
"_"+bones_names[num]
77 hand_dict[bone_name]=[prev_bone_name,bone_tf]
79 prev_bone_name=bone_name
80 prev_bone_absolute=bone_absolute
82 tip=PyKDL.Frame(PyKDL.Rotation(1,0,0, 0,1,0, 0,0,1),PyKDL.Vector(0,0,-bone.length/1000.0))
83 hand_dict[finger_name+
"_tip"]=[prev_bone_name,tip]
93 for tf_name,tf_array
in hand_dict.items():
95 tf_prev_name=tf_array[0]
96 br.sendTransform(tf_matrix.p,tf_matrix.M.GetQuaternion(),timenow,tf_name,tf_prev_name)
104 rospy.init_node(
'leap_skeleton_pub')
107 while not rospy.is_shutdown():
108 timenow=rospy.Time.now()
109 if li.listener.left_hand:
111 if li.listener.right_hand:
118 if __name__ ==
'__main__':
121 except rospy.ROSInterruptException:
def relative_frame(frame_A, frame_B)
def make_tf_dict(hand, hand_name)
def broadcast_hand(hand, hand_name, timenow)
def make_kdl_frame(leap_basis_matrix, leap_position_vector, is_left=False)