diff --git a/ros/gamepad/src/config.py b/ros/gamepad/src/config.py index 326037f..ebdfcd6 100644 --- a/ros/gamepad/src/config.py +++ b/ros/gamepad/src/config.py @@ -1,61 +1,91 @@ MIN_ABS_DIFFERENCE = 0 # New ranges for the triggers and sticks (Probably need to adjust these values) -TRIGGER_DEAD_ZONE = 0.09 -TRIGGER_RANGE = 1.0 STICK_DEAD_ZONE = 0.09 -STICK_RANGE = 1.0 - -# Mapping of JoyAxisMotion events to gamepad_state keys -# The number is the axis given by pygame -JOY_AXIS = {1: "LSY", 0: "LSX", 4: "RSY", 3: "RSX", 2: "LT", 5: "RT"} - -# Mapping of JoyButton events to gamepad_state keys -# The number is the button given by pygame -JOY_BUTTON = { - 3: "Y", - 1: "B", - 0: "A", - 2: "X", - 9: "LSZ", - 10: "RSZ", - 4: "LB", - 5: "RB", - 8: "XBOX", - 6: "START", - 7: "MENU", +AXIS_RANGE = 1.0 +# Scale factors for the translational and rotational axes +SCALE_TRANSLATIONAL_X = 1.0 +SCALE_TRANSLATIONAL_Y = 1.0 +SCALE_TRANSLATIONAL_Z = 1.0 +SCALE_ROTATIONAL_X = 1.0 +SCALE_ROTATIONAL_Y = 1.0 +SCALE_ROTATIONAL_Z = 1.0 +# Trim values for the translational axes +# Values are added to the translational axis values after scaling +TRIM_X = 0.0 +TRIM_Y = 0.0 +TRIM_Z = 0.0 + +GAMEPAD_TIMEOUT = 20 # seconds + +JOYSTICK_NAME = "Thrustmaster T.16000M" +THROTTLE_NAME = "Thrustmaster TWCS Throttle" + +# Store the states of the throttle axies +throttle_axis_state = { + 0: 0.0, # throttle back joystick x axis (left-to-right) + 1: 0.0, # throttle back joystick y axis (up-and-down) + 2: 0.0, # throttle slide + 3: 0.0, # unknown + 4: 0.0, # unknown + 5: 0.0, # throttle back paddle + 6: 0.0, # unknown + 7: 0.0 # throttle left slider +} + +# Store the states of the throttle buttons +throttle_button_state = { + 0: 0, # throttle right bottom (orange) button + 1: 0, # throttle back left (orange) button + 2: 0, # throttle back right (orange) button + 3: 0, # throttle back right rocker button up + 4: 0, # throttle back right rocker button down + 5: 0, # throttle back joystick button + 6: 0, # throttle right middle button up + 7: 0, # throttle right middle button forward + 8: 0, # throttle right middle button down + 9: 0, # throttle right middle button back + 10: 0, # throttle right bottm button up + 11: 0, # throttle right bottom button forward + 12: 0, # throttle right bottom button down + 13: 0 # throttle right bottom button back } -JOY_BUTTON_KEY = { - "Y": 3, - "B": 1, - "A": 0, - "X": 2, - "LSZ": 9, - "RSZ": 10, - "LB": 4, - "RB": 5, - "XBOX": 8, - "START": 6, - "MENU": 7, + +# Store the state of throttle hats +throttle_hat_state = { + 0: 0, # throttle hat (right top button) front-to-back (left-to-right) + 1: 0 # throttle hat (right top button) up-and-down +} + +# Store the states of the joystick axes +joystick_axis_state = { + 0: 0.0, # joystick y axis movement (left-to-right) + 1: 0.0, # joystick x axis movement (front-to-back) + 2: 0.0, # joystick yaw movement (twist) + 3: 0.0 # bottom controller slider +} + +# Store the states of the joystick buttons +joystick_button_state = { + 0: 0, # joystick trigger + 1: 0, # joystick top bottom button + 2: 0, # joystick top left button + 3: 0, # joystick top right button + 4: 0, # joystick left top left button + 5: 0, # joystick left top middle button + 6: 0, # joystick left top right button + 7: 0, # joystick left bottom right button + 8: 0, # joystick left bottom middle button + 9: 0, # joystick left bottom left button + 10: 0, # joystick right top right button + 11: 0, # joystick right top middle button + 12: 0, # joystick right top left button + 13: 0, # joystick right bottom left button + 14: 0, # joystick right bottom middle button + 15: 0 # joystick right bottom right button } -gamepad_state = { - "LSX": 0.0, - "LSY": 0.0, - "RSX": 0.0, - "RSY": 0.0, - "LT": -1.0, - "RT": -1.0, - "DPADX": 0, - "DPADY": 0, - "Y": 0, - "B": 0, - "A": 0, - "X": 0, - "LSZ": 0, - "RSZ": 0, - "LB": 0, - "RB": 0, - "XBOX": 0, - "START": 0, - "MENU": 0, +# Stores the states of the joystick hats +joystick_hat_state = { + 0: 0, # joystick hat y axis position (left-to-right) + 1: 0 # joystick hat x axis position (front-to-back) } diff --git a/ros/gamepad/src/sender.py b/ros/gamepad/src/sender.py index dcd65ab..db3e017 100644 --- a/ros/gamepad/src/sender.py +++ b/ros/gamepad/src/sender.py @@ -6,265 +6,245 @@ # ROS import rclpy +from rclpy.node import Node from std_msgs.msg import String, Bool, Empty from shared_msgs.msg import RovVelocityCommand, ToolsCommandMsg from geometry_msgs.msg import Twist from config import * - -tools = [0, 0, 0, 0, 0] - -SCALE_TRANSLATIONAL_X = 1.0 -SCALE_TRANSLATIONAL_Y = 1.0 -SCALE_TRANSLATIONAL_Z = 1.0 - -SCALE_ROTATIONAL_X = 1.0 -SCALE_ROTATIONAL_Y = 1.0 -SCALE_ROTATIONAL_Z = 1.0 - -TRIM_X = 0.0 -TRIM_Y = 0.0 -TRIM_Z = 0.0 - -REVERSE = 1 -LOCKOUT = True -# is fine = 0 = std_mode -# is_fine = 1 = fine_mode -# is_fine = 2 = yeet mode -is_fine = 0 -is_pool_centric = False -depth_lock = False -pitch_lock = False -GAMEPAD_TIMEOUT = 20 # seconds - - -def getMessage(): - """Returns a RovVelocityCommand message based on the current gamepad state""" - global gamepad_state - global is_fine - global is_pool_centric - global pitch_lock - global depth_lock - - t = Twist() - - t.linear.x = -(gamepad_state["LSY"] * SCALE_TRANSLATIONAL_X + TRIM_X) * REVERSE - t.linear.y = -(gamepad_state["LSX"] * SCALE_TRANSLATIONAL_Y + TRIM_Y) * REVERSE - t.linear.z = ( - (gamepad_state["RT"] - gamepad_state["LT"]) / 2.0 - ) * SCALE_TRANSLATIONAL_Z + TRIM_Z - - if gamepad_state["LB"] == 1: - x = 1 * SCALE_ROTATIONAL_X - elif gamepad_state["RB"] == 1: - x = -1 * SCALE_ROTATIONAL_X - else: - x = 0.0 - - t.angular.x = -x - t.angular.y = (-gamepad_state["RSY"] * SCALE_ROTATIONAL_Y) * REVERSE - t.angular.z = -gamepad_state["RSX"] * SCALE_ROTATIONAL_Z - - new_msg = RovVelocityCommand() - new_msg.twist = t - new_msg.is_fine = is_fine - new_msg.is_pool_centric = is_pool_centric - new_msg.depth_lock = depth_lock - new_msg.pitch_lock = pitch_lock - - return new_msg - - -def getTools(): - """Returns a ToolsCommandMsg message based on the current gamepad state""" - global tools - - tm = ToolsCommandMsg() - tm.tools = [i for i in tools] - - return tm - - -def correct_raw(raw, abbv): - """Corrects the raw value from the gamepad to be in the range [-1.0, 1.0]""" - # Separate the sign from the value - sign = (raw >= 0) * 2 - 1 - raw = abs(raw) - - # Check if the input is a trigger or a stick - if abbv == "LT" or abbv == "RT": - dead_zone = TRIGGER_DEAD_ZONE - value_range = TRIGGER_RANGE - else: - dead_zone = STICK_DEAD_ZONE - value_range = STICK_RANGE - - if raw < dead_zone: - return 0.0 - - # Remove dead zone and scale the value - raw -= dead_zone - raw *= value_range / (value_range - dead_zone) - raw = 1.0 if raw > value_range else raw / value_range - corrected = round(raw, 3) - corrected *= sign - return corrected - - -def process_event(event): - """Processes a pygame event""" - global tools - global is_fine - global gamepad_state - global is_pool_centric - global depth_lock - global pitch_lock - - # Button pressed down events - if event.type == pygame.JOYBUTTONDOWN: - gamepad_state[JOY_BUTTON[event.button]] = 1 - if event.button == JOY_BUTTON_KEY["A"]: - tools[0] = not tools[0] - - elif event.button == JOY_BUTTON_KEY["B"]: - tools[1] = not tools[1] - - elif event.button == JOY_BUTTON_KEY["X"]: - tools[2] = not tools[2] - - elif event.button == JOY_BUTTON_KEY["Y"] and LOCKOUT: - tools[3] = not tools[3] - - elif event.button == JOY_BUTTON_KEY["MENU"]: - is_pool_centric = not is_pool_centric - - # Button released events - elif event.type == pygame.JOYBUTTONUP: - gamepad_state[JOY_BUTTON[event.button]] = 0 - - # DPAD buttons - elif event.type == pygame.JOYHATMOTION: - if event.value[1] == 1: - if is_fine < 3: - is_fine += 1 - elif event.value[1] == -1: - if is_fine > 0: - is_fine -= 1 - else: - pass - if event.value[0] == -1: - pitch_lock = not pitch_lock - elif event.value[0] == 1: - depth_lock = not depth_lock - is_pool_centric = True - else: - pass - - # Joysticks - elif event.type == pygame.JOYAXISMOTION: - gamepad_state[JOY_AXIS[event.axis]] = correct_raw( - event.value, JOY_AXIS[event.axis] - ) - - # If the gamepad is disconnected, try to reconnect it - elif event.type == pygame.JOYDEVICEREMOVED: - if not reconnect_gamepad(): - node.get_logger().info("\nNo gamepad found, exiting") - pygame.quit() - rclpy.shutdown() - sys.exit(0) - - -def pub_data(): - """Publishes the data to the rov_velocity topic and the tools topic""" - # Get a message to publish for the rov_velocity topic - pub.publish(getMessage()) - # Get a message to publish for the tools topic - pub_tools.publish(getTools()) - - -def update_gamepad(): - """Updates the gamepad state""" - # Get all the events from pygame and process them - for event in pygame.event.get(): - process_event(event) - - -def init_pygame(): - """Initializes pygame and the joystick""" - global joystick - pygame.init() - pygame.joystick.init() - assert pygame.joystick.get_count() == 1 - joystick = pygame.joystick.Joystick(0) - - -def reconnect_gamepad(): - """Tries to reconnect the gamepad""" - global joystick - reconnected = False - i = GAMEPAD_TIMEOUT - while i >= 0 and not reconnected: +class Controller(Node): + def __init__(self): + super().__init__("gp_pub") + # Pygame variables + self.joystick = None + self.throttle = None + self.joystick_id = 0 + self.throttle_id = 0 + + # Joystick and throttle states + self.joystick_axis_state = joystick_axis_state + self.joystick_button_state = joystick_button_state + self.throttle_axis_state = throttle_axis_state + self.throttle_button_state = throttle_button_state + + # Pilot variables + self.reverse = 1 + self.lockout = True + self.is_fine = 0 + self.is_pool_centric = False + self.depth_lock = False + self.pitch_lock = False + self.tools = [0, 0, 0, 0, 0] + + # Mapping variables (TO CHANGE MAPPING: GO TO getMessage() AND MAKE YOUR CHANGES THERE) + self.mapping = 1 # 0, 1, 2, 3 + try: - node.get_logger().info( - "Gamepad disconnected, reconnect within {:2} seconds".format(i) - ) - pygame.init() - pygame.joystick.init() - # make sure there is only one joystick - if pygame.joystick.get_count() == 1: - # get the first joystick - joystick = pygame.joystick.Joystick(0) + self.init_pygame() + except: + self.get_logger().info('Controllers not found. Please make sure both the joystick and throttle are connected') + if not self.reconnect(): + self.get_logger().info("\nNo gamepad found, exiting") + pygame.quit() + sys.exit(0) + + # Create the publishers + self.pub = self.create_publisher(RovVelocityCommand, '/rov_velocity', 10) + self.pub_tools = self.create_publisher(ToolsCommandMsg, 'tools', 10) + + # Create the timers + self.data_thread = self.create_timer(0.1, self.pub_data) + self.gamepad_thread = self.create_timer(0.001, self.update) + self.get_logger().info('Controllers initialized') + + + def init_pygame(self): + '''Initializes pygame and the joystick''' + pygame.init() + pygame.joystick.init() + # Should be two joysticks + assert pygame.joystick.get_count() == 2 + + # Determine which joystick is the joystick and which is the throttle + for i in range(pygame.joystick.get_count()): + if pygame.joystick.Joystick(i).get_name() == JOYSTICK_NAME: + self.joystick = pygame.joystick.Joystick(i) + self.joystick_id = i + if pygame.joystick.Joystick(i).get_name() == THROTTLE_NAME: + self.throttle = pygame.joystick.Joystick(i) + self.throttle_id = i + + + def reconnect(self): + '''Tries to reconnect the gamepad''' + reconnected = False + i = GAMEPAD_TIMEOUT + while i >= 0 and not reconnected: + self.get_logger().info('Gamepad disconnected, reconnect within {:2} seconds'.format(i)) + try: + self.init_pygame() reconnected = True + except: + pygame.time.wait(1000) # Wait 1 second + i -= 1 + + if reconnected: + self.get_logger().info('Controllers reconnected') + + return reconnected + + + def update(self): + '''Updates the gamepad state''' + # Get all the events from pygame and process them + for event in pygame.event.get(): + self.process_event(event) + + + def correct_raw(self, raw): + '''Corrects the raw value from the gamepad to be in the range [-1.0, 1.0]''' + if raw > 0: + if raw >= STICK_DEAD_ZONE: + return raw + elif raw > 1: + return 1 + else: + return 0 + + if raw < 0: + if raw <= -STICK_DEAD_ZONE: + return raw + elif raw < -1: + return -1 else: + return 0 + + + def process_event(self, event): + '''Processes a pygame event''' + # Check if the event is a joyaxismotion event + if event.type == pygame.JOYAXISMOTION: + # Check if the event is from the joystick or the throttle + if event.joy == self.joystick_id: + self.joystick_axis_state[event.axis] = self.correct_raw(event.value) + elif event.joy == self.throttle_id: + self.throttle_axis_state[event.axis] = self.correct_raw(event.value) + + # Check if the event is a joybuttondown event + elif event.type == pygame.JOYBUTTONDOWN: + # Check if the event is from the joystick or the throttle + if event.joy == self.joystick_id: + self.joystick_button_state[event.button] = 1 + + elif event.joy == self.throttle_id: + self.throttle_button_state[event.button] = 1 + + # Check if the event is a joybuttonup event + elif event.type == pygame.JOYBUTTONUP: + # Check if the event is from the joystick or the throttle + if event.joy == self.joystick_id: + self.joystick_button_state[event.button] = 0 + elif event.joy == self.throttle_id: + self.throttle_button_state[event.button] = 0 + + self.changed_trigger = False + if self.joystick_button_state[0] == 1 and self.changed_trigger == False: + self.tools[0] = not self.tools[0] + self.changed_trigger = True + + if self.joystick_button_state[0] == 0: + self.changed_trigger = False + + self.change_buttom = False + if self.joystick_button_state[1] == 1 and self.change_buttom == False: + self.tools[2] = not self.tools[2] + self.change_buttom = True + + if self.joystick_button_state[1] == 0: + self.change_buttom = False + + + # Check if the event is a joydeviceremoved event + elif event.type == pygame.JOYDEVICEREMOVED: + # Try to reconnect the gamepad + self.get_logger().info('Controller disconnected. Attempting to reconnect...') + if not self.reconnect(): + self.get_logger().info("\nNo gamepad found, exiting") pygame.quit() - assert False - except: - # wait 1 second - pygame.time.wait(1000) - i -= 1 + sys.exit(0) + - if reconnected: - node.get_logger().info("\nGamepad reconnected") - joystick = pygame.joystick.Joystick(0) + def pub_data(self): + '''Publishes the data to the rov_velocity topic and the tools topic''' + # Get a message to publish for the rov_velocity topic + self.pub.publish(self.getMessage()) + # Get a message to publish for the tools topic + self.pub_tools.publish(self.getTools()) - return reconnected + def getMessage(self): + '''Returns a RovVelocityCommand message based on the current gamepad state''' -if __name__ == "__main__": - global pub, pub_tools, data_thread, gamepad_thread, node - # Initialize the ros node - rclpy.init() - node = rclpy.create_node("gp_pub") + t = Twist() - try: - init_pygame() - except: - node.get_logger().info("No gamepad found, please connect a gamepad") - if not reconnect_gamepad(): - node.get_logger().info("\nNo gamepad found, exiting") - pygame.quit() - sys.exit(0) + if self.mapping == 0: + # Set linear velocities + t.linear.x = -(self.throttle_axis_state[2] * SCALE_TRANSLATIONAL_X + TRIM_X) * self.reverse + t.linear.y = -(self.throttle_axis_state[5] * SCALE_TRANSLATIONAL_Y + TRIM_Y) * self.reverse + t.linear.z = -(self.throttle_axis_state[1] * SCALE_TRANSLATIONAL_Y + TRIM_Y) * self.reverse - # Create the publishers - pub = node.create_publisher(RovVelocityCommand, "/rov_velocity", 10) - pub_tools = node.create_publisher(ToolsCommandMsg, "tools", 10) + # Set angular velocities + t.angular.x = -(self.joystick_axis_state[1] * SCALE_ROTATIONAL_X) * self.reverse + t.angular.y = -(self.joystick_axis_state[0] * SCALE_ROTATIONAL_Y) * self.reverse + t.angular.z = -(self.joystick_axis_state[2] * SCALE_ROTATIONAL_Z) * self.reverse - # Create the timers - data_thread = node.create_timer(0.1, pub_data) - gamepad_thread = node.create_timer(0.001, update_gamepad) + # Set PM + # PM_grab = self.joystick_button_state[0] + # PM_pos = self.joystick_button_state[1] - print("ready") + else: + # Set linear velocities + t.linear.x = -(self.joystick_axis_state[1] * SCALE_TRANSLATIONAL_X + TRIM_X) * self.reverse + t.linear.y = (self.joystick_axis_state[0] * SCALE_TRANSLATIONAL_Y + TRIM_Y) * self.reverse + t.linear.z = -(self.throttle_axis_state[2] * SCALE_TRANSLATIONAL_Y + TRIM_Y) * self.reverse + + # Set angular velocities + t.angular.x = 0.0 # no pitch + t.angular.y = 0.0 # no roll + t.angular.z = -(self.joystick_axis_state[2] * SCALE_ROTATIONAL_Z) * self.reverse + + # Set PM + # PM_grab = self.joystick_button_state[0] + # PM_pos = self.joystick_button_state[1] + + new_msg = RovVelocityCommand() + new_msg.twist = t + new_msg.is_fine = self.is_fine + new_msg.is_pool_centric = self.is_pool_centric + new_msg.depth_lock = self.depth_lock + new_msg.pitch_lock = self.pitch_lock - rclpy.spin(node) + return(new_msg) + + def getTools(self): + '''Returns a ToolsCommandMsg message based on the current gamepad state''' - data_thread.destroy() - gamepad_thread.destroy() + tm = ToolsCommandMsg() + tm.tools = [i for i in self.tools] - # Stop the pygame library - pygame.quit() + return tm - node.destroy_node() + + +def main(): + rclpy.init(args=None) + controller = Controller() + rclpy.spin(controller) + controller.destroy_node() rclpy.shutdown() + +if __name__ == '__main__': + main() + diff --git a/scripts/build.sh b/scripts/build.sh index fba29a8..8c662ac 100755 --- a/scripts/build.sh +++ b/scripts/build.sh @@ -1,4 +1,4 @@ -#!/usr/bin/bash +#!/bin/bash source /opt/ros/humble/setup.bash colcon build diff --git a/test/controller_mapping.py b/test/controller_mapping.py new file mode 100644 index 0000000..91508fa --- /dev/null +++ b/test/controller_mapping.py @@ -0,0 +1,173 @@ +import pygame +import sys +import time + +'''instance_id attribute for events does not work and i don't know why''' + +'''x-axis is foward and backward, y-axis is side to side, z-axis is twisting''' +CONT_AXIS_KEY = { + 'X':1, 'Y':0, 'Z':2, 'SLIDE':3 +} + +THR_AXIS_KEY = { + 'THR':2, 'YAW':3, 'SCR':4, 'SX':0, 'SY':1 +} + +CONT_AXIS = { + 1:'X', 0:'Y', 2:'Z', 3:'SLIDE' +} + +THR_AXIS = { + 2:'THR', 3:'YAW', 4:'SCR', 0:'SX', 1:'SY' +} + + +CONT_BUTTON_KEY = { + 'trigger':0, '2':1, '3':2, '4':3, '5':4, '6':5, '7':6, '8':7, '9':8, '10':9, '11':10, '12':11, '13':12, '14':13, + '15':14, '16':15 +} + +CONT_BUTTON = { + 0:'trigger', 1:'2', 2:'3', 3:'4', 4:'5', 5:'6', 6:'7', 7:'8', 8:'9', 9:'10', 10:'11', 11:'12', 12:'13', 13:'14', + 14:'15', 15:'16' +} + +THR_BUTTON_KEY = { + 0:'T1', 1:'T2', 2:'T3', 3:'T4', 4:'T5', 5:'T6', 6:'T7', 7:'T8', 8:'T9', 9:'T10', 10:'T11', 11:'T12', 12:'T13', 13:'T14' +} + +THR_BUTTON = { + 'T1':0, 'T2':1, 'T3':2, 'T4':3, 'T5':4, 'T6':5, 'T7':6, 'T8':7, 'T9':8, 'T10':9, 'T11':10, 'T12':11, 'T13':12, 'T14':13 +} + +axis_state = { + 'X':0.0, + 'Y':0.0, + 'Z':0.0, + 'SLIDE':0.0, + 'THR':0.0, + 'SCR':0.0, + 'YAW':0.0, + 'SX':0.0, + 'SY':0.0 +} + +button_state = { + 'trigger':0, + '2':0, + '3':0, + '4':0, + '5':0, + '6':0, + '7':0, + '8':0, + '9':0, + '10':0, + '11':0, + '12':0, + '13':0, + '14':0, + '15':0, + '16':0, + 'T1':0, + 'T2':0, + 'T3':0, + 'T4':0, + 'T5':0, + 'T6':0, + 'T7':0, + 'T8':0, + 'T9':0, + 'T10':0, + 'T11':0, + 'T12':0, + 'T13':0, + 'T14':0 +} + +hat_state = [ + 0, 0 +] + + +no_controller = False +wtf = False + + +def init_pygame(): + '''Initializes pygame and the joystick''' + global controller + global throttle + pygame.init() + pygame.joystick.init() + '''check if controller connected''' + if(pygame.joystick.get_count() != 2): + print("Not two controllers") + pygame.quit() + sys.exit(0) + controller = pygame.joystick.Joystick(0) + throttle = pygame.joystick.Joystick(1) + + +'''get the controller events and update the various states accodingly''' +def check_event(): + for event in pygame.event.get(): + print(event.instance_id) + if event.instance_id == 0: + if event.type == pygame.JOYAXISMOTION: + axis_state[CONT_AXIS[event.axis]] = event.value + elif event.type == pygame.JOYBUTTONDOWN: + button_state[CONT_BUTTON[event.button]] = 1 + elif event.type == pygame.JOYBUTTONUP: + button_state[CONT_BUTTON[event.button]] = 0 + elif event.type == pygame.JOYDEVICEREMOVED: + print('Disconnect') + pygame.quit() + sys.exit(0) + if event.instance_id == 1: + if event.type == pygame.JOYAXISMOTION: + axis_state[THR_AXIS[event.axis]] = event.value + elif event.type == pygame.JOYBUTTONDOWN: + button_state[THR_BUTTON[event.button]] = 1 + elif event.type == pygame.JOYBUTTONUP: + button_state[THR_BUTTON[event.button]] = 0 + elif event.type == pygame.JOYDEVICEREMOVED: + print('Disconnect') + pygame.quit() + sys.exit(0) + + + + + +'''logger to log the axis states to the command line''' +def state_logger(): + for axis, state in axis_state.items(): + print(f"Axis {axis} = {state}", end=' ') + print() + + # for button, state in button_state.items(): + # print(f"Button {button} = {state}") + + + + + + + +if __name__ == '__main__': + init_pygame() + print(pygame.__version__) + while True: + try: + check_event() + state_logger() + except KeyboardInterrupt: + pygame.quit() + sys.exit(0) + except: + pass + time.sleep(1) + + + \ No newline at end of file