sender.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 __author__ = 'flier'
00003 import rospy
00004 import leap_interface
00005 from leap_motion.msg import leap
00006 from leap_motion.msg import leapros
00007 
00008 # Obviously, this method publishes the data defined in leapros.msg to /leapmotion/data
00009 def sender():
00010     li = leap_interface.Runner()
00011     li.setDaemon(True)
00012     li.start()
00013     # pub     = rospy.Publisher('leapmotion/raw',leap)
00014     pub_ros   = rospy.Publisher('leapmotion/data',leapros)
00015     rospy.init_node('leap_pub')
00016 
00017     while not rospy.is_shutdown():
00018         hand_direction_   = li.get_hand_direction()
00019         hand_normal_      = li.get_hand_normal()
00020         hand_palm_pos_    = li.get_hand_palmpos()
00021         hand_pitch_       = li.get_hand_pitch()
00022         hand_roll_        = li.get_hand_roll()
00023         hand_yaw_         = li.get_hand_yaw()
00024         msg = leapros()
00025         msg.direction.x = hand_direction_[0]
00026         msg.direction.y = hand_direction_[1]
00027         msg.direction.z = hand_direction_[2]
00028         msg.normal.x = hand_normal_[0]
00029         msg.normal.y = hand_normal_[1]
00030         msg.normal.z = hand_normal_[2]
00031         msg.palmpos.x = hand_palm_pos_[0]
00032         msg.palmpos.y = hand_palm_pos_[1]
00033         msg.palmpos.z = hand_palm_pos_[2]
00034         msg.ypr.x = hand_yaw_
00035         msg.ypr.y = hand_pitch_
00036         msg.ypr.z = hand_roll_
00037         # We don't publish native data types, see ROS best practices
00038         # pub.publish(hand_direction=hand_direction_,hand_normal = hand_normal_, hand_palm_pos = hand_palm_pos_, hand_pitch = hand_pitch_, hand_roll = hand_roll_, hand_yaw = hand_yaw_)
00039         pub_ros.publish(msg)
00040         # Save some CPU time, circa 100Hz publishing.
00041         rospy.sleep(0.01)
00042 
00043 
00044 if __name__ == '__main__':
00045     try:
00046         sender()
00047     except rospy.ROSInterruptException:
00048         pass


leap_motion
Author(s): Florian Lier
autogenerated on Mon Oct 6 2014 01:47:15