mirror of
https://github.com/OSURoboticsClub/Rover_2017_2018.git
synced 2025-11-09 02:31:14 +00:00
Made joystick multi-threaded
This commit is contained in:
@@ -20,17 +20,7 @@ from rover_drive.msg import RoverMotorDrive
|
|||||||
# Global Variables
|
# Global Variables
|
||||||
#####################################
|
#####################################
|
||||||
GAME_CONTROLLER_NAME = "Logitech Logitech Extreme 3D Pro"
|
GAME_CONTROLLER_NAME = "Logitech Logitech Extreme 3D Pro"
|
||||||
CONTROLLER_DATA_UPDATE_FREQUENCY = 100 # Times per second
|
CONTROLLER_DATA_UPDATE_FREQUENCY = 10 # Times per second
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
|
||||||
# Controller Class Definition
|
|
||||||
#####################################
|
|
||||||
|
|
||||||
# ########## Signals ##########
|
|
||||||
controller_connection_aquired = QtCore.pyqtSignal(bool)
|
|
||||||
controller_update_ready_signal = QtCore.pyqtSignal()
|
|
||||||
|
|
||||||
|
|
||||||
#####################################
|
#####################################
|
||||||
# Controller Class Definition
|
# Controller Class Definition
|
||||||
@@ -103,12 +93,7 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
"BTN_NORTH": "x_pressed",
|
"BTN_NORTH": "x_pressed",
|
||||||
"BTN_WEST": "y_pressed"
|
"BTN_WEST": "y_pressed"
|
||||||
}
|
}
|
||||||
|
self.ready = False
|
||||||
self.last_time = time.time()
|
|
||||||
|
|
||||||
rospy.init_node("drive_tester")
|
|
||||||
|
|
||||||
self.pub = rospy.Publisher("/drive/motoroneandtwo", RoverMotorDrive, queue_size=1)
|
|
||||||
|
|
||||||
self.start()
|
self.start()
|
||||||
|
|
||||||
@@ -121,14 +106,8 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
self.setup_controller_flag = False
|
self.setup_controller_flag = False
|
||||||
if self.data_acquisition_and_broadcast_flag:
|
if self.data_acquisition_and_broadcast_flag:
|
||||||
self.__get_controller_data()
|
self.__get_controller_data()
|
||||||
self.__broadcast_if_ready()
|
|
||||||
|
|
||||||
# self.msleep(100)
|
self.msleep(10)
|
||||||
|
|
||||||
|
|
||||||
# noinspection PyUnresolvedReferences
|
|
||||||
def connect_signals_to_slots__slot(self):
|
|
||||||
pass
|
|
||||||
|
|
||||||
|
|
||||||
def __setup_controller(self):
|
def __setup_controller(self):
|
||||||
@@ -146,36 +125,57 @@ class LogitechJoystick(QtCore.QThread):
|
|||||||
for event in events:
|
for event in events:
|
||||||
if event.code in self.raw_mapping_to_class_mapping:
|
if event.code in self.raw_mapping_to_class_mapping:
|
||||||
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
|
self.controller_states[self.raw_mapping_to_class_mapping[event.code]] = event.state
|
||||||
|
self.ready = True
|
||||||
# print "Logitech: %s" % self.controller_states
|
# 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()
|
current_time = time.time()
|
||||||
|
|
||||||
if (current_time - self.last_time) > (1 / CONTROLLER_DATA_UPDATE_FREQUENCY):
|
if (current_time - self.last_time) > (1 / CONTROLLER_DATA_UPDATE_FREQUENCY):
|
||||||
drive = RoverMotorDrive()
|
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_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.pub.publish(drive)
|
||||||
self.last_time = current_time
|
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__':
|
if __name__ == '__main__':
|
||||||
qapp = QtCore.QCoreApplication(sys.argv)
|
qapp = QtCore.QCoreApplication(sys.argv)
|
||||||
|
|
||||||
joystick = LogitechJoystick()
|
joystick = Publisher()
|
||||||
|
|
||||||
qapp.exec_()
|
qapp.exec_()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
Reference in New Issue
Block a user