Go to the documentation of this file.00001
00002
00003 import rospy
00004 import struct
00005 import select
00006 import os
00007 import pyudev
00008
00009 try:
00010 from sensor_msgs.msg import Joy
00011 except:
00012 import roslib; roslib.load_manifest("joy_mouse")
00013 from sensor_msgs.msg import Joy
00014
00015
00016
00017 def lookupDeviceFileByNameAttribute(name, prefix="mouse"):
00018 """
00019 lookup device by name attribute. You can check name by
00020 udevadmin info -a -n /dev/input/mouse0
00021 """
00022 context = pyudev.Context()
00023 for device in context.list_devices(subsystem="input"):
00024 for a in device.attributes:
00025 if a == "name" and device.attributes[a] == name:
00026 for child in device.children:
00027 if child.sys_name.startswith(prefix):
00028 return os.path.join("/dev", "input", child.sys_name)
00029
00030 def main(device_name, autorepeat_rate, frame_id):
00031 rospy.loginfo("reading %s" % (device_name))
00032 joy_pub = rospy.Publisher('joy', Joy)
00033 with open(device_name, "rb" ) as tp_file:
00034 prev_bLeft = 0
00035 prev_bMiddle = 0
00036 prev_bRight = 0
00037 while not rospy.is_shutdown():
00038 if autorepeat_rate == 0:
00039 buf = tp_file.read(3)
00040 else:
00041 r,w,e = select.select([tp_file], [], [], 1.0 / autorepeat_rate)
00042 if tp_file in r:
00043 buf = os.read(tp_file.fileno(), 3)
00044 else:
00045 buf = None
00046 if buf == None:
00047 x, y = (0, 0)
00048 bLeft = prev_bLeft
00049 bMiddle = prev_bMiddle
00050 bRight = prev_bRight
00051 else:
00052 button = ord( buf[0] )
00053 bLeft = button & 0x1
00054 bMiddle = ( button & 0x4 ) > 0
00055 bRight = ( button & 0x2 ) > 0
00056 x,y = struct.unpack( "bb", buf[1:] )
00057 joy_msg = Joy()
00058 joy_msg.header.stamp = rospy.Time.now()
00059 joy_msg.header.frame_id = frame_id
00060 joy_msg.axes = [x, y]
00061 joy_msg.buttons = [bLeft, bMiddle, bRight]
00062 joy_pub.publish(joy_msg)
00063 prev_bLeft = bLeft
00064 prev_bMiddle = bMiddle
00065 prev_bRight = bRight