Go to the documentation of this file.00001
00002 __author__ = 'flier'
00003
00004 import argparse
00005
00006 import rospy
00007 import leap_interface
00008 from leap_motion.msg import leap
00009 from leap_motion.msg import leapros
00010
00011 FREQUENCY_ROSTOPIC_DEFAULT = 0.01
00012 NODENAME = 'leap_pub'
00013 PARAMNAME_FREQ = 'freq'
00014 PARAMNAME_FREQ_ENTIRE = '/' + NODENAME + '/' + PARAMNAME_FREQ
00015
00016 def sender():
00017 '''
00018 This method publishes the data defined in leapros.msg to /leapmotion/data
00019 '''
00020 rospy.loginfo("Parameter set on server: PARAMNAME_FREQ={}".format(rospy.get_param(PARAMNAME_FREQ_ENTIRE, FREQUENCY_ROSTOPIC_DEFAULT)))
00021
00022 li = leap_interface.Runner()
00023 li.setDaemon(True)
00024 li.start()
00025
00026 pub_ros = rospy.Publisher('leapmotion/data',leapros, queue_size=2)
00027 rospy.init_node(NODENAME)
00028
00029 while not rospy.is_shutdown():
00030 hand_direction_ = li.get_hand_direction()
00031 hand_normal_ = li.get_hand_normal()
00032 hand_palm_pos_ = li.get_hand_palmpos()
00033 hand_pitch_ = li.get_hand_pitch()
00034 hand_roll_ = li.get_hand_roll()
00035 hand_yaw_ = li.get_hand_yaw()
00036
00037 msg = leapros()
00038 msg.direction.x = hand_direction_[0]
00039 msg.direction.y = hand_direction_[1]
00040 msg.direction.z = hand_direction_[2]
00041 msg.normal.x = hand_normal_[0]
00042 msg.normal.y = hand_normal_[1]
00043 msg.normal.z = hand_normal_[2]
00044 msg.palmpos.x = hand_palm_pos_[0]
00045 msg.palmpos.y = hand_palm_pos_[1]
00046 msg.palmpos.z = hand_palm_pos_[2]
00047 msg.ypr.x = hand_yaw_
00048 msg.ypr.y = hand_pitch_
00049 msg.ypr.z = hand_roll_
00050
00051 fingerNames = ['thumb', 'index', 'middle', 'ring', 'pinky']
00052 fingerPointNames = ['metacarpal', 'proximal',
00053 'intermediate', 'distal', 'tip']
00054 for fingerName in fingerNames:
00055 for fingerPointName in fingerPointNames:
00056 pos = li.get_finger_point(fingerName, fingerPointName)
00057 for iDim, dimName in enumerate(['x', 'y', 'z']):
00058 setattr(getattr(msg, '%s_%s' % (fingerName, fingerPointName)),
00059 dimName, pos[iDim])
00060
00061
00062
00063 pub_ros.publish(msg)
00064 rospy.sleep(rospy.get_param(PARAMNAME_FREQ_ENTIRE, FREQUENCY_ROSTOPIC_DEFAULT))
00065
00066
00067 if __name__ == '__main__':
00068 try:
00069 sender()
00070 except rospy.ROSInterruptException:
00071 pass