skeleton_sender.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 
3 __author__ = 'Igor Zubrycki'
4 
5 """ For backwards compatibility with the old driver files
6  Will be DELETED in the future """
7 
8 import rospy
9 import leap_interface
10 import tf
11 import sys
12 import Leap
13 import math
14 import roslib
15 import rospy
16 from std_msgs.msg import String
17 from std_msgs.msg import Float64
18 import std_msgs.msg
19 import sensor_msgs.msg
20 import actionlib_msgs.msg
21 import trajectory_msgs.msg
22 import collections
23 import scipy.signal as signal
24 import geometry_msgs.msg
25 import PyKDL
26 
27 finger_names=["thumb","index","middle","ring","pinky"]
28 bones_names=["metacarpal","proximal","intermediate","distal"]
29 
30 def make_kdl_frame(leap_basis_matrix,leap_position_vector,is_left=False):
31  # Makes kdl frame from Leap Motion matrix and vector formats
32 
33  if is_left:
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())
37 
38  else:
39  basis=leap_basis_matrix.to_array_3x3()
40  rotation_mat=PyKDL.Rotation(*basis).Inverse()
41  # rotation_mat=PyKDL.Rotation(*[1,0,0,0,1,0,0,0,1])#.Inverse()
42  placement=PyKDL.Vector(*leap_position_vector.to_float_array())/1000.0 #to m
43  return PyKDL.Frame(rotation_mat,placement)
44 
45 def relative_frame(frame_A,frame_B):
46 
47  return (frame_A.Inverse())*frame_B
48 
49 
50 hand_ground_tf=PyKDL.Frame(PyKDL.Rotation.EulerZYX(0, 0, math.pi/2.0),PyKDL.Vector(0,0,0))
51 
52 def make_tf_dict(hand,hand_name):
53 
54  hand_dict={}
55  # hand_ground_tf=
56  hand_dict["hand_ground"]=["ground",hand_ground_tf]
57 
58 
59  hand_tf=make_kdl_frame(hand.basis,hand.palm_position,hand.is_left)
60  # hand_tf=make_kdl_frame(hand.basis,hand.palm_position)
61  hand_dict[hand_name]=["hand_ground",hand_tf]
62  for finger in hand.fingers:
63  finger_name=hand_name+"_"+finger_names[finger.type]
64 
65  prev_bone_name=hand_name
66  for num in range(0,4):
67 
68  bone=finger.bone(num)
69 
70  bone_absolute=make_kdl_frame(bone.basis,bone.prev_joint,hand.is_left)
71  if num==0:
72  bone_tf=relative_frame(hand_tf,bone_absolute)
73  else:
74  bone_tf=relative_frame(prev_bone_absolute,bone_absolute)
75 
76  bone_name=finger_name+"_"+bones_names[num]
77  hand_dict[bone_name]=[prev_bone_name,bone_tf]
78 
79  prev_bone_name=bone_name
80  prev_bone_absolute=bone_absolute
81 
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]
84  return hand_dict
85  # now sending to ROS
86 
87 
88 def broadcast_hand(hand,hand_name,timenow):
89  hand_dict=make_tf_dict(hand,hand_name)
91 
92 
93  for tf_name,tf_array in hand_dict.items():
94  tf_matrix=tf_array[1]
95  tf_prev_name=tf_array[0]
96  br.sendTransform(tf_matrix.p,tf_matrix.M.GetQuaternion(),timenow,tf_name,tf_prev_name)
97 
98 def sender():
100  li.setDaemon(True)
101  li.start()
102  # pub = rospy.Publisher('leapmotion/raw',leap)
103  # pub_ros = rospy.Publisher('leapmotion/data',leapros)
104  rospy.init_node('leap_skeleton_pub')
105 
106 
107  while not rospy.is_shutdown():
108  timenow=rospy.Time.now()
109  if li.listener.left_hand:
110  broadcast_hand(li.listener.left_hand,"left_hand",timenow)
111  if li.listener.right_hand:
112  broadcast_hand(li.listener.right_hand,"right_hand",timenow)
113 
114  # save some CPU time, circa 100Hz publishing.
115  rospy.sleep(0.01)
116 
117 
118 if __name__ == '__main__':
119  try:
120  sender()
121  except rospy.ROSInterruptException:
122  pass
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)
Definition: sender.py:1


leap_motion
Author(s): Florian Lier , Mirza Shah , Isaac IY Saito
autogenerated on Tue Jun 2 2020 03:58:01