__init__.py
Go to the documentation of this file.
1 import roslib; roslib.load_manifest('joy_listener')
2 import rospy
3 from sensor_msgs.msg import Joy
4 
5 class JoyListener(dict):
6  def __init__(self, wait_time=1.0, joy_topic='/joy'):
7  self.wait_time = wait_time
8  self.sub = rospy.Subscriber(joy_topic, Joy, self.joy_cb, queue_size=1)
9  self.last_time = rospy.Time(0)
10  self.axes_cb = None
11 
12  def joy_cb(self, msg):
13  buttons = msg.buttons
14  now = rospy.Time.now()
15  if (now- self.last_time ).to_sec() < self.wait_time:
16  return
17 
18  for button, function in self.iteritems():
19  if buttons[button]:
20  self.last_time = now
21  function()
22  break
23 
24  if self.axes_cb:
25  self.axes_cb(msg.axes)
26 
27 PS3_BUTTONS = ['select', 'left_joy', 'right_joy', 'start', 'up', 'right', 'down', 'left', 'l2', 'r2', 'l1', 'r1', 'triangle', 'circle', 'x', 'square', 'ps3']
28 def PS3(name):
29  return PS3_BUTTONS.index(name)
30 
31 
32 WII_BUTTONS = ['1', '2', 'a', 'b', '+', '-', 'left', 'right', 'up', 'down', 'home']
33 
34 def WII(name):
35  return WII_BUTTONS.index(name)
def __init__(self, wait_time=1.0, joy_topic='/joy')
Definition: __init__.py:6
def PS3(name)
Definition: __init__.py:28
def joy_cb(self, msg)
Definition: __init__.py:12
def WII(name)
Definition: __init__.py:34


joy_listener
Author(s): David V. Lu!!
autogenerated on Fri Jun 7 2019 22:01:10