joy.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import rospy
4 import struct
5 import select
6 import os
7 import pyudev
8 
9 try:
10  from sensor_msgs.msg import Joy
11 except:
12  import roslib; roslib.load_manifest("joy_mouse")
13  from sensor_msgs.msg import Joy
14 
15  #def main(device_name, rate, frame_id):
16 
17 def lookupDeviceFileByNameAttribute(name, prefix="mouse"):
18  """
19  lookup device by name attribute. You can check name by
20  udevadmin info -a -n /dev/input/mouse0
21  """
22  context = pyudev.Context()
23  for device in context.list_devices(subsystem="input"):
24  for a in device.attributes:
25  if a == "name" and device.attributes[a] == name:
26  for child in device.children:
27  if child.sys_name.startswith(prefix):
28  return os.path.join("/dev", "input", child.sys_name)
29 
30 def main(device_name, autorepeat_rate, frame_id):
31  rospy.loginfo("reading %s" % (device_name))
32  joy_pub = rospy.Publisher('joy', Joy)
33  with open(device_name, "rb" ) as tp_file:
34  prev_bLeft = 0
35  prev_bMiddle = 0
36  prev_bRight = 0
37  while not rospy.is_shutdown():
38  if autorepeat_rate == 0:
39  buf = tp_file.read(3)
40  else:
41  r,w,e = select.select([tp_file], [], [], 1.0 / autorepeat_rate)
42  if tp_file in r:
43  buf = os.read(tp_file.fileno(), 3)
44  else:
45  buf = None
46  if buf == None:
47  x, y = (0, 0)
48  bLeft = prev_bLeft
49  bMiddle = prev_bMiddle
50  bRight = prev_bRight
51  else:
52  button = ord( buf[0] )
53  bLeft = button & 0x1
54  bMiddle = ( button & 0x4 ) > 0
55  bRight = ( button & 0x2 ) > 0
56  x,y = struct.unpack( "bb", buf[1:] )
57  joy_msg = Joy()
58  joy_msg.header.stamp = rospy.Time.now()
59  joy_msg.header.frame_id = frame_id
60  joy_msg.axes = [x, y]
61  joy_msg.buttons = [bLeft, bMiddle, bRight]
62  joy_pub.publish(joy_msg)
63  prev_bLeft = bLeft
64  prev_bMiddle = bMiddle
65  prev_bRight = bRight
def lookupDeviceFileByNameAttribute(name, prefix="mouse")
Definition: joy.py:17
def main(device_name, autorepeat_rate, frame_id)
Definition: joy.py:30


joy_mouse
Author(s):
autogenerated on Fri May 14 2021 02:51:44