Ps3Subscriber.py
Go to the documentation of this file.
00001 import rospy
00002 from sensor_msgs.msg import Joy
00003 from Signal import Signal
00004 
00005 class Ps3Subscriber(object):
00006 
00007     top_button = 'top'
00008     right_button = 'right'
00009     bottom_button = 'bottom'
00010     left_button = 'left'
00011 
00012     select_button = 'select'
00013     start_button = 'start'
00014 
00015     square_button = 'square'
00016     triangle_button = 'triangle'
00017     cross_button = 'cross'
00018     circle_button = 'circle'
00019 
00020     def __init__(self):
00021         self.buttons_changed = Signal()
00022         self._buttons = None
00023         self._pressed_buttons = set()
00024         rospy.Subscriber('ps3_joy', Joy, self._joy_callback)
00025 
00026     def _joy_callback(self, joy_msg):
00027         if self._buttons != joy_msg.buttons:
00028             self._buttons = joy_msg.buttons
00029             self.buttons_changed.emit()
00030 
00031     def get_triggered_buttons(self):
00032         buttons = {
00033             4: self.top_button,
00034             5: self.right_button,
00035             6: self.bottom_button,
00036             7: self.left_button,
00037             0: self.select_button,
00038             3: self.start_button,
00039             15: self.square_button,
00040             12: self.triangle_button,
00041             14: self.cross_button,
00042             13: self.circle_button,
00043         }
00044         triggered = set()
00045         for index, value in enumerate(self._buttons):
00046             if index in buttons.keys():
00047                 index = buttons[index]
00048             if value != 0:
00049                 if index not in self._pressed_buttons:
00050                     self._pressed_buttons.add(index)
00051                     triggered.add(index)
00052             else:
00053                 if index in self._pressed_buttons:
00054                     self._pressed_buttons.remove(index)
00055         return triggered


slider_gui
Author(s): Dirk Thomas
autogenerated on Thu Jun 6 2019 20:32:11