Made joystick multi-threaded

This commit is contained in:
2018-02-22 23:24:04 -08:00
parent aa46f6637a
commit 1aaf00ddbe

View File

@@ -20,17 +20,7 @@ from rover_drive.msg import RoverMotorDrive
# Global Variables
#####################################
GAME_CONTROLLER_NAME = "Logitech Logitech Extreme 3D Pro"
CONTROLLER_DATA_UPDATE_FREQUENCY = 100 # Times per second
#####################################
# Controller Class Definition
#####################################
# ########## Signals ##########
controller_connection_aquired = QtCore.pyqtSignal(bool)
controller_update_ready_signal = QtCore.pyqtSignal()
CONTROLLER_DATA_UPDATE_FREQUENCY = 10 # Times per second
#####################################
# Controller Class Definition
@@ -103,12 +93,7 @@ class LogitechJoystick(QtCore.QThread):
"BTN_NORTH": "x_pressed",
"BTN_WEST": "y_pressed"
}
self.last_time = time.time()
rospy.init_node("drive_tester")
self.pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=1)
self.ready = False
self.start()
@@ -121,14 +106,8 @@ class LogitechJoystick(QtCore.QThread):
self.setup_controller_flag = False
if self.data_acquisition_and_broadcast_flag:
self.__get_controller_data()
self.__broadcast_if_ready()
# self.msleep(100)
# noinspection PyUnresolvedReferences
def connect_signals_to_slots__slot(self):
pass
self.msleep(10)
def __setup_controller(self):
@@ -146,36 +125,57 @@ class LogitechJoystick(QtCore.QThread):
for event in events:
if event.code in self.raw_mapping_to_class_mapping:
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
self.ready = True
# print "Logitech: %s" % self.controller_states
def __broadcast_if_ready(self):
#####################################
# Controller Class Definition
#####################################
class Publisher(QtCore.QThread):
def __init__(self):
super(Publisher, self).__init__()
self.joystick = LogitechJoystick()
while not self.joystick.ready:
self.msleep(100)
# ########## Thread Flags ##########
self.run_thread_flag = True
rospy.init_node("drive_tester")
self.pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=1)
self.last_time = time.time()
self.start()
def run(self):
while self.run_thread_flag:
self.__update_and_publish()
self.msleep(20)
def __update_and_publish(self):
current_time = time.time()
if (current_time - self.last_time) > (1 / CONTROLLER_DATA_UPDATE_FREQUENCY):
drive = RoverMotorDrive()
axis = self.controller_states["left_stick_y_axis"]
axis = self.joystick.controller_states["left_stick_y_axis"]
drive.first_motor_direction = 1 if axis <= 512 else 0
drive.first_motor_speed = min(abs(self.controller_states["left_stick_y_axis"] - 512) * 128, 65535)
drive.first_motor_speed = min(abs(self.joystick.controller_states["left_stick_y_axis"] - 512) * 128, 65535)
self.pub.publish(drive)
self.last_time = current_time
def on_kill_threads__slot(self):
self.terminate() # DON'T normally do this!!!!!
self.run_thread_flag = False
if __name__ == '__main__':
qapp = QtCore.QCoreApplication(sys.argv)
joystick = LogitechJoystick()
joystick = Publisher()
qapp.exec_()