joy.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 import rospy
00004 import struct
00005 import select
00006 import os
00007 try:
00008     from sensor_msgs.msg import Joy
00009 except:
00010     import roslib; roslib.load_manifest("joy_mouse")
00011     from sensor_msgs.msg import Joy
00012 
00013     #def main(device_name, rate, frame_id):
00014 def main(device_name, autorepeat_rate, frame_id):
00015     rospy.loginfo("reading %s" % (device_name))
00016     joy_pub = rospy.Publisher('joy', Joy)
00017     with open(device_name, "rb" ) as tp_file:
00018         prev_bLeft = 0
00019         prev_bMiddle = 0
00020         prev_bRight = 0
00021         while not rospy.is_shutdown():
00022             if autorepeat_rate == 0:
00023                 buf = tp_file.read(3)
00024             else:
00025                 r,w,e = select.select([tp_file], [], [], 1.0 / autorepeat_rate)
00026                 if tp_file in r:
00027                     buf = os.read(tp_file.fileno(), 3)
00028                 else:
00029                     buf = None
00030             if buf == None:
00031                 x, y = (0, 0)
00032                 bLeft = prev_bLeft
00033                 bMiddle = prev_bMiddle
00034                 bRight = prev_bRight
00035             else:
00036                 button = ord( buf[0] )
00037                 bLeft = button & 0x1
00038                 bMiddle = ( button & 0x4 ) > 0
00039                 bRight = ( button & 0x2 ) > 0
00040                 x,y = struct.unpack( "bb", buf[1:] )
00041             joy_msg = Joy()
00042             joy_msg.header.stamp = rospy.Time.now()
00043             joy_msg.header.frame_id = frame_id
00044             joy_msg.axes = [x, y]
00045             joy_msg.buttons = [bLeft, bMiddle, bRight]
00046             joy_pub.publish(joy_msg)
00047             prev_bLeft = bLeft
00048             prev_bMiddle = bMiddle
00049             prev_bRight = bRight


joy_mouse
Author(s):
autogenerated on Mon Oct 6 2014 01:10:54