diff --git a/kits/igor2/README.md b/kits/igor2/README.md new file mode 100644 index 0000000..d056743 --- /dev/null +++ b/kits/igor2/README.md @@ -0,0 +1,38 @@ +# Igor Balancing Robot Matlab Demo + +## Requirements + +### Controller + +The demo can be run using either a gamecontroller or Mobile IO device acessible from the computer running the demo. + +* USB controller (Must be compatibile with SDL2 - check [here](https://github.com/gabomdq/SDL_GameControllerDB/blob/master/gamecontrollerdb.txt) for your controller) +* Mobile IO (Requires HEBI's Mobile IO app on an Android or iOS device) + +### Software Requirements +* [HEBI Python API](https://pypi.org/project/hebi-py/) +* [PySDL2](https://pypi.org/project/PySDL2/) + * **Linux Users:** You should check if your distro has a package for this already. For Ubuntu, install the [pysdl2 package](https://launchpad.net/ubuntu/+source/pysdl2) + * If not installing through a package manager, make sure you have the SDL2 library installed! + +## Running + +Simply run the `igor2_demo.py` file located at `kits/igor2`. Both Python 2 and 3 are supported, but note that Python 2 upstream will become [unsupported 1 Jan 2020.](https://pythonclock.org/) + +Note: By default, the demo will look for a Mobile IO device with family `HEBI` and name `Mobile IO`. You must provide `--joystick` if you want to control Igor using a USB gamecontroller. + +## Controls + +The demo provides default mappings for both supported controllers. You can modify them, if needed, by editing the `components/configuration.py` file directly. + +### Game Controller + +The default gamecontroller mappings are as followed. Note that the image is of a generic Sony Playstation 4 controller, but the concept applies to all other SDL2 compatible controllers. +![ps4 igor](resources/ps4_igor.png) + +*Note: To exit idle mode, press L3 (press in left axis stick)* + +### Mobile IO + +The default Mobile IO mappings are as followed. Note that the layout of the application may appear different on your device than what is shown, but the buttons and axes are guaranteed across any device. +![mobile io igor](resources/mobile_io_igor.png) diff --git a/kits/igor2/components/arm.py b/kits/igor2/components/arm.py index 3546110..933eefd 100644 --- a/kits/igor2/components/arm.py +++ b/kits/igor2/components/arm.py @@ -252,3 +252,18 @@ def set_wrist_velocity(self, value): self.acquire_value_lock() self._user_commanded_wrist_velocity = value self.release_value_lock() + + def reset_state(self): + super(Arm, self).reset_state() + + self._user_commanded_grip_velocity.fill(0) + self._current_xyz.fill(0) + np.copyto(self._grip_pos, self._home_ef[0:3, 3]) + np.copyto(self._grip_pos, self._new_grip_pos) + np.copyto(self._joint_angles, self.home_angles.reshape((4, 1))) + self._joint_velocities.fill(0) + self._joint_efforts.fill(0) + self._user_commanded_wrist_velocity = 0.0 + self._grav_comp_torque.fill(0) + self._current_det_actual = 0.0 + self._current_det_expected = 0.0 diff --git a/kits/igor2/components/body.py b/kits/igor2/components/body.py index 1ca0b69..5a0bbe1 100644 --- a/kits/igor2/components/body.py +++ b/kits/igor2/components/body.py @@ -272,3 +272,32 @@ def update_position(self): masses = self._masses np.sum(np.multiply(self._current_xyz, matlib.repmat(masses.T, 3, 1)), axis=1, out=self._com) self._com *= 1.0/self.mass + + def reset_state(self): + """ + Used when transitioning Igor back into idle mode. + """ + self._fbk_position.fill(0) + self._fbk_position_cmd.fill(0) + self._fbk_velocity.fill(0) + self._fbk_velocity_err.fill(0) + self._xyz_error.fill(0) + self._pos_error.fill(0) + self._vel_error.fill(0) + self._impedance_err.fill(0) + self._impedance_torque.fill(0) + self._current_tip_fk.fill(0) + self._current_j_actual.fill(0) + self._current_j_actual_f.fill(0) + self._current_j_expected.fill(0) + self._current_j_expected_f.fill(0) + + if self._current_xyz is not None: + self._current_xyz.fill(0) + + # TODO: is this necessary? + self._home_angles__flat = self._home_angles.A1 + self._fbk_position__flat = self._fbk_position.A1 + self._fbk_position_cmd__flat = self._fbk_position_cmd.A1 + self._fbk_velocity__flat = self._fbk_velocity.A1 + self._fbk_velocity_err__flat = self._fbk_velocity_err.A1 diff --git a/kits/igor2/components/chassis.py b/kits/igor2/components/chassis.py index 98c5555..22035b4 100644 --- a/kits/igor2/components/chassis.py +++ b/kits/igor2/components/chassis.py @@ -23,7 +23,7 @@ def _create_trajectory(self): self._jerks) def __init__(self, val_lock): - super(Chassis, self).__init__(val_lock, mass=6.0, com=[0.0, 0.0, 0.10+0.3]) + super(Chassis, self).__init__(val_lock, mass=6.0, com=[-0.05, 0.0, 0.10+0.3]) self._user_commanded_directional_velocity = 0.0 self._user_commanded_yaw_velocity = 0.0 self._min_ramp_time = 0.5 @@ -79,6 +79,11 @@ def update_trajectory(self, user_commanded_knee_velocity, user_commanded_grip_ve t = time_now - self._time_s self._time_s = time_now + if t > self._trajectory.end_time: + # Clamp to end time to prevent undesired trajectory calculations. + # This can lead to issues when re-entering running mode after entering idle mode from running mode + t = self._trajectory.end_time + # --------------------------------------------- # Smooth the trajectories for various commands. # This will be the starting waypoint for the new trajectory. @@ -294,3 +299,16 @@ def set_yaw_velocity(self, velocity): self._user_commanded_yaw_velocity = velocity self.release_value_lock() + def reset_state(self): + self._user_commanded_directional_velocity = 0.0 + self._user_commanded_yaw_velocity = 0.0 + self._hip_pitch = 0.0 + self._hip_pitch_velocity = 0.0 + self._velocity_feedforward = 0.0 + self._velocity_error = 0.0 + self._velocity_error_cumulative = 0.0 + self._lean_angle_error = 0.0 + self._lean_angle_error_cumulative = 0.0 + self._cmd_chassis_vel_last = 0.0 + self._fbk_chassis_vel_last = 0.0 + self._calculated_lean_angle = 0.0 diff --git a/kits/igor2/components/configuration.py b/kits/igor2/components/configuration.py index f4c3ad2..e3365a9 100644 --- a/kits/igor2/components/configuration.py +++ b/kits/igor2/components/configuration.py @@ -1,9 +1,10 @@ import os from util.input.joystick import Joystick +from util.input.module_controller import HebiModuleController # ------------------------------------------------------------------------------ -# Joystick selectors +# Controller selectors # ------------------------------------------------------------------------------ @@ -35,7 +36,21 @@ def _joystick_by_name_selector(name): return None -def _create_joystick_selector(strategy, arg=None): +def _controller_by_mobile_io_selector(family, name, feedback_frequency): + import hebi + from time import sleep + lookup = hebi.Lookup() + sleep(2) + group = lookup.get_group_from_names([family], [name]) + if group is None: + msg = 'Could not find Mobile IO on network with\nfamily: {0}\nname: {1}'.format(family, name) + print(msg) + raise RuntimeError(msg) + group.feedback_frequency = feedback_frequency + return HebiModuleController(group) + + +def _create_controller_selector(strategy, arg=None): if strategy == 'first': return _joystick_first_available_selector elif strategy == 'index': @@ -44,14 +59,127 @@ def _create_joystick_selector(strategy, arg=None): elif strategy == 'name': assert arg is not None return lambda: _joystick_by_name_selector(arg) + elif strategy == 'mobile_io': + assert arg is not None + return lambda: _controller_by_mobile_io_selector(arg[0], arg[1], arg[2]) else: - raise RuntimeError('Invalid strategy {0}'.format(strategy)) + raise RuntimeError('Invalid controller selector strategy {0}'.format(strategy)) + + +# ------------------------------------------------------------------------------ +# Controller Mappings +# ------------------------------------------------------------------------------ + + +class IgorControllerMapping(object): + __slots__ = ('_arm_vel_x', '_arm_vel_y', '_stance_height', '_wrist_vel', + '_chassis_yaw', '_chassis_vel', '_exit_idle_modle', '_quit', '_balance_controller_toggle', + '_soft_shutdown', '_lower_arm', '_raise_arm', '_stance_height_control_strategy', + '_wrist_velocity_control_strategy') + + def __init__(self, arm_vel_x, arm_vel_y, stance_height, wrist_vel, chassis_yaw, + chassis_vel, exit_idle_modle, quit, balance_controller_toggle, soft_shutdown, + lower_arm, raise_arm, stance_height_control_strategy, wrist_velocity_control_strategy): + + self._arm_vel_x = arm_vel_x + self._arm_vel_y = arm_vel_y + self._stance_height = stance_height + self._wrist_vel = wrist_vel + self._chassis_yaw = chassis_yaw + self._chassis_vel = chassis_vel + self._exit_idle_modle = exit_idle_modle + self._quit = quit + self._balance_controller_toggle = balance_controller_toggle + self._soft_shutdown = soft_shutdown + self._lower_arm = lower_arm + self._raise_arm = raise_arm + if stance_height_control_strategy == 'SLIDER': + if type(stance_height) is not str: + raise TypeError('stance_height must be a string for `SLIDER` stance height control strategy') + elif stance_height_control_strategy == 'TRIGGERS': + if type(stance_height) is not tuple: + raise TypeError('stance_height must be a tuple for `TRIGGERS` stance height control strategy') + else: + raise ValueError('Invalid stance height control strategy {0}'.format(stance_height_control_strategy)) + + if wrist_velocity_control_strategy == 'SLIDER': + if type(wrist_vel) is not str: + raise TypeError('wrist_vel must be a string for `SLIDER` wrist velocity control strategy') + elif wrist_velocity_control_strategy == 'BUTTONS': + if type(wrist_vel) is not tuple: + raise TypeError('wrist_vel must be a tuple for `BUTTONS` wrist velocity control strategy') + else: + raise ValueError('Invalid wrist velocity control strategy {0}'.format(wrist_velocity_control_strategy)) + + self._wrist_velocity_control_strategy = wrist_velocity_control_strategy + self._stance_height_control_strategy = stance_height_control_strategy + + @property + def arm_vel_x(self): + return self._arm_vel_x + + @property + def arm_vel_y(self): + return self._arm_vel_y + + @property + def stance_height(self): + return self._stance_height + + @property + def wrist_vel(self): + return self._wrist_vel + + @property + def chassis_yaw(self): + return self._chassis_yaw + + @property + def chassis_vel(self): + return self._chassis_vel + + @property + def exit_idle_modle(self): + return self._exit_idle_modle + + @property + def quit(self): + return self._quit + + @property + def balance_controller_toggle(self): + return self._balance_controller_toggle + + @property + def soft_shutdown(self): + return self._soft_shutdown + + @property + def lower_arm(self): + return self._lower_arm + + @property + def raise_arm(self): + return self._raise_arm + + @property + def stance_height_control_strategy(self): + return self._stance_height_control_strategy + + @property + def wrist_velocity_control_strategy(self): + return self._wrist_velocity_control_strategy + + +_default_joystick_mapping = IgorControllerMapping('LEFT_STICK_Y', 'LEFT_STICK_X', ('L2', 'R2'), ('DPAD_DOWN', 'DPAD_UP'), 'RIGHT_STICK_X', 'RIGHT_STICK_Y', 'L3', 'SHARE', 'TOUCHPAD', 'OPTIONS', 'L1', 'R1', 'TRIGGERS', 'BUTTONS') +_default_mobile_io_mapping = IgorControllerMapping('a2', 'a1', 'a3', 'a6', 'a7', 'a8', 'b3', 'b1', 'b2', 'b4', 'b8', 'b6', 'SLIDER', 'SLIDER') # ------------------------------------------------------------------------------ # Configuration # ------------------------------------------------------------------------------ + class Igor2Config(object): """ Used when starting up Igor II. @@ -74,74 +202,66 @@ def __init__(self, imitation=False): self.__default_gains_no_cam = os.path.join(resource_path, 'igorGains_noCamera.xml') self.__imitation = imitation self.__find_joystick_strategy = None + self.__controller_mapping = None self.select_first_available_joystick() def select_joystick_by_name(self, name): """ Set the joystick selection strategy to select a joystick by name """ - self.__find_joystick_strategy = _create_joystick_selector('name', name) + self.__find_joystick_strategy = _create_controller_selector('name', name) + self.__controller_mapping = _default_joystick_mapping def select_joystick_by_index(self, index): """ Set the joystick selection strategy to select a joystick by index """ - self.__find_joystick_strategy = _create_joystick_selector('index', index) + self.__find_joystick_strategy = _create_controller_selector('index', index) + self.__controller_mapping = _default_joystick_mapping def select_first_available_joystick(self): """ Set the joystick selection strategy to select the first available joystick """ - self.__find_joystick_strategy = _create_joystick_selector('first') + self.__find_joystick_strategy = _create_controller_selector('first') + self.__controller_mapping = _default_joystick_mapping - @property - def module_names(self): + def select_controller_by_mobile_io(self, family, name, feedback_frequency=200): """ - :return: - :rtype: list + Set the joystick selection strategy to select a mobile IO module with the provided family and name """ + self.__find_joystick_strategy = _create_controller_selector('mobile_io', (family, name, feedback_frequency)) + self.__controller_mapping = _default_mobile_io_mapping + + @property + def module_names(self): return self.__module_names @property def module_names_no_cam(self): - """ - :return: - :rtype: list - """ return self.__module_names[0:-1] @property def family(self): - """ - :return: - :rtype: str - """ return self.__family @property def gains_xml(self): - """ - :return: - :rtype: str - """ return self.__default_gains @property def gains_no_camera_xml(self): - """ - :return: - :rtype: str - """ return self.__default_gains_no_cam @property def is_imitation(self): - """ - :return: - :rtype: bool - """ return self.__imitation @property def joystick_selector(self): return self.__find_joystick_strategy + + @property + def controller_mapping(self): + return self.__controller_mapping + diff --git a/kits/igor2/components/igor.py b/kits/igor2/components/igor.py index 0b0ead4..7a8b604 100644 --- a/kits/igor2/components/igor.py +++ b/kits/igor2/components/igor.py @@ -100,6 +100,7 @@ def create_group(config, has_camera): def connect(): group = lookup.get_group_from_names(families, names) if group is None: + print('Cannot find igor on network...') raise RuntimeError() elif group.size != len(names): raise RuntimeError() @@ -167,17 +168,23 @@ def _ensure_started(self): self._state_lock.release() raise RuntimeError('Igor has not been started (igor.start() was not called)') - def _pending_quit(self): + def _should_continue(self): """ Contract: This method assumes the caller has acquired `_state_lock` """ - return self._quit_flag + if not is_main_thread_active() or self._quit_flag: + return False - def _continue(self): - """ - Contract: This method assumes the caller has acquired `_state_lock` - """ - return is_main_thread_active() and not self._pending_quit() + if self._transition_to_idle_possible: + # Check if stance is low enough to transition to idle + return self._left_leg.knee_angle < 2.5 + + return True + + def _transition_from_idle_to_running(self, ts, pressed): + """Controller event handler to transition from idle to running mode""" + if pressed: + self._leave_idle_flag = True # ------------------------------------------------ # Calculations @@ -352,10 +359,48 @@ def _calculate_lean_angle(self): # Actions # ------------------------------------------------ + def _enter_idle(self): + group = self._group + group_command = self._group_command + + from time import sleep + + if self._num_spins > 0: + # This is not the first time we have been in the idle state. We will clear + # the state of the body objects before beginning the loop below. + self._chassis.reset_state() + self._left_leg.reset_state() + self._right_leg.reset_state() + self._left_arm.reset_state() + self._right_arm.reset_state() + # Stop commanding while in idle + group_command.clear() + + self._leave_idle_flag = False + while not self._leave_idle_flag: + if self._quit_flag: + # User requested to quit, so bail out before actually being instructed to go into running mode. + return + + group_command.led.color = 'magenta' + group.send_command(group_command) + sleep(0.1) + group_command.led.color = 'green' + group.send_command(group_command) + sleep(0.1) + + # Let module control the LED color + group_command.led.color = 'transparent' + group.send_command(group_command) + def _soft_startup(self): """ Performs the startup phase, which takes about 3 seconds """ + if self._quit_flag: + # Can happen if user was in running mode, re-entered idle, then requested to quit during idle + return + l_arm = self._left_arm r_arm = self._right_arm l_leg = self._left_leg @@ -565,52 +610,69 @@ def _spin_once(self, bc): # Lifecycle functions # ------------------------------------------------ + def _on_stop(self): + for entry in self._on_stop_callbacks: + entry() + def _stop(self): """ Stop running Igor. This happens once the user requests the demo to stop, or when the running application begins to shut down. - This is only called by :meth:`__start`l_leg """ - if self._restart_flag: - # Prepare for a restart - # TODO - pass - else: - # TODO - print('Shutting down Igor...') - duration = self._stop_time - self._start_time - tics = float(self._num_spins) - avg_frequency = tics/duration - print('Ran for: {0} seconds.'.format(duration)) - print('Average processing frequency: {0} Hz'.format(avg_frequency)) + print('Shutting down Igor...') + duration = self._stop_time - self._start_time + tics = float(self._num_spins) + avg_frequency = tics/duration + #print('Ran for: {0} seconds.'.format(duration)) + #print('Average processing frequency: {0} Hz'.format(avg_frequency)) + + # Set the LED color strategy back to the default + self._group_command.clear() + self._group_command.led.color = 'transparent' + self._group.send_command_with_acknowledgement(self._group_command) + + self._on_stop() def _start(self): """ Main processing method. This runs on a background thread. """ - self._soft_startup() + first_run = True + while True: + self._enter_idle() + self._soft_startup() + + # Delay registering event handlers until now, so Igor + # can start up without being interrupted by user commands. + # View this function in `event_handlers.py` to see + # all of the joystick event handlers registered + if first_run: + try: + register_igor_event_handlers(self) + except Exception as e: + print('Caught exception while registering event handlers:\n{0}'.format(e)) + self._start_time = time() + first_run = False - # Delay registering event handlers until now, so Igor - # can start up without being interrupted by user commands. - # View this function in `event_handlers.py` to see - # all of the joystick event handlers registered - try: - register_igor_event_handlers(self) - except: - pass - - self._start_time = time() - self._state_lock.acquire() - while self._continue(): - # We have `_state_lock` at this point. Access fields here before releasing lock - bc = self._balance_controller_enabled - self._state_lock.release() - self._spin_once(bc) - self._num_spins = self._num_spins + 1 self._state_lock.acquire() + while self._should_continue(): + bc = self._balance_controller_enabled + self._state_lock.release() + self._spin_once(bc) + self._num_spins = self._num_spins + 1 + self._state_lock.acquire() + + if self._quit_flag: + self._stop_time = time() + self._state_lock.release() + self._stop() + # Break out if quit was requested + return + else: + self._state_lock.release() - self._stop_time = time() - self._stop() + def add_on_stop_callback(self, callback): + self._on_stop_callbacks.append(callback) # ------------------------------------------------ # Initialization functions @@ -643,6 +705,8 @@ def __init__(self, has_camera=False, config=None): self._proc_thread = None + self._on_stop_callbacks = list() + # ---------------- # Parameter fields self._has_camera = has_camera @@ -657,7 +721,8 @@ def __init__(self, has_camera=False, config=None): self._started = False self._balance_controller_enabled = True self._quit_flag = False - self._restart_flag = False + self._transition_to_idle_possible = False + self._leave_idle_flag = False self._time_last = np.empty(num_dofs, dtype=np.float64) self._diff_time = np.empty(num_dofs, dtype=np.float64) value_lock = Lock() @@ -771,7 +836,19 @@ def start(self): self._group_info = hebi.GroupInfo(group.size) joystick_selector = self._config.joystick_selector - self._joy = joystick_selector() + + while True: + try: + joy = joystick_selector() + if joy is None: + raise RuntimeError + self._joy = joy + break + except: + pass + + self._joy.add_button_event_handler(self._config.controller_mapping.exit_idle_modle, self._transition_from_idle_to_running) + load_gains(self) from threading import Condition, Lock, Thread @@ -817,17 +894,16 @@ def request_stop(self): self._quit_flag = True self._state_lock.release() - def request_restart(self): + def allow_transition_to_idle(self, value): """ - Send a request to restart the demo. + Set if the transition back to idle mode is allowed if igor is crouched low enough. If the demo has not been started, this method raises an exception. :raises RuntimeError: if `start()` has not been called """ self._state_lock.acquire() self._ensure_started() - self._restart_flag = True - self._quit_flag = True + self._transition_to_idle_possible = bool(value) self._state_lock.release() def set_balance_controller_state(self, state): diff --git a/kits/igor2/components/joystick_interface.py b/kits/igor2/components/joystick_interface.py index a9d4921..0aa67da 100644 --- a/kits/igor2/components/joystick_interface.py +++ b/kits/igor2/components/joystick_interface.py @@ -1,12 +1,12 @@ -from functools import partial as funpart from util import math_utils + # ------------------------------------------------------------------------------ # Arm Event Handlers # ------------------------------------------------------------------------------ -def arm_x_vel_event(igor, in_deadzone_func, ts, axis_value): +def arm_x_vel_event(igor, vel_calc, ts, axis_value): """ Event handler when left stick Y-Axis motion occurs. This event handler will set the given arm's velocity in the X axis to @@ -20,17 +20,12 @@ def arm_x_vel_event(igor, in_deadzone_func, ts, axis_value): :param ts: (ignored) :param axis_value: [-1,1] value of the axis """ - if in_deadzone_func(axis_value): - igor.left_arm.set_x_velocity(0.0) - igor.right_arm.set_x_velocity(0.0) - else: - scale = -0.4 - axis_value = scale*axis_value - igor.left_arm.set_x_velocity(scale*axis_value) - igor.right_arm.set_x_velocity(scale*axis_value) + vel = vel_calc(axis_value) + igor.left_arm.set_x_velocity(vel) + igor.right_arm.set_x_velocity(vel) -def arm_y_vel_event(igor, in_deadzone_func, ts, axis_value): +def arm_y_vel_event(igor, vel_calc, ts, axis_value): """ Event handler when left stick X-Axis motion occurs. This event handler will set the given arm's velocity in the Y axis to @@ -44,197 +39,150 @@ def arm_y_vel_event(igor, in_deadzone_func, ts, axis_value): :param ts: (ignored) :param axis_value: [-1,1] value of the axis """ - if in_deadzone_func(axis_value): - igor.left_arm.set_y_velocity(0.0) - igor.right_arm.set_y_velocity(0.0) - else: - scale = -0.4 - axis_value = scale*axis_value - igor.left_arm.set_y_velocity(axis_value) - igor.right_arm.set_y_velocity(axis_value) + vel = vel_calc(axis_value) + igor.left_arm.set_y_velocity(vel) + igor.right_arm.set_y_velocity(vel) -def arm_z_vel_event_l(igor, ts, axis_value): +def arm_z_vel_lower_event(igor, raise_btn_id, ts, button_value): """ - Event handler when left trigger of joystick has its axis value changed - (Left Trigger Axis event handler) + Event handler to respond to lowering arm (z direction) request - :param igor: (bound parameter) - :param ts: (ignored) - :param axis_value: [-1,1] value of the axis + :param igor: (bound parameter) + :param raise_btn_id: (bound parameter) + :param ts: (ignored) + :param button_value: button pressed state """ - # Left Trigger - # map [-1,1] to [0,1] - axis_value = -0.2*(axis_value*0.5+0.5) - set_arm_vel_z(igor.left_arm, axis_value) - set_arm_vel_z(igor.right_arm, axis_value) + # If raise_btn_id is pressed too, just ignore this + if igor.joystick.get_button(raise_btn_id): + return + + if button_value: + igor.left_arm.set_z_velocity(-0.2) + igor.right_arm.set_z_velocity(-0.2) + else: + igor.left_arm.set_z_velocity(0.0) + igor.right_arm.set_z_velocity(0.0) -def arm_z_vel_event_r(igor, ts, axis_value): +def arm_z_vel_raise_event(igor, lower_btn_id, ts, button_value): """ - Event handler when right trigger of joystick has its axis value changed - (Right Trigger Axis event handler) + Event handler to respond to raising arm (z direction) request - :param igor: (bound parameter) - :param ts: (ignored) - :param axis_value: [-1,1] value of the axis + :param igor: (bound parameter) + :param ts: (ignored) + :param button_value: button pressed state """ - # Right Trigger - # map [-1,1] to [0,1] - axis_value = 0.2*(axis_value*0.5+0.5) - set_arm_vel_z(igor.left_arm, axis_value) - set_arm_vel_z(igor.right_arm, axis_value) - + # If lower_btn_id is pressed too, just ignore this + if igor.joystick.get_button(lower_btn_id): + return -def zero_arm_z_event(igor, both_triggers_released, ts, pressed): - """ - Event handler when left or right trigger of joystick is pressed or released. - This event handler will zero the Z axis velocity of the arms, if both joysticks - are not being pressed. If this condition is not satisfied, then this function - does nothing. - - :param igor: (bound parameter) - :param both_triggers_released: (bound parameter) - :param ts: (ignored) - :param pressed: (ignored) - """ - if both_triggers_released(): + if button_value: + igor.left_arm.set_z_velocity(0.2) + igor.right_arm.set_z_velocity(0.2) + else: igor.left_arm.set_z_velocity(0.0) igor.right_arm.set_z_velocity(0.0) -def wrist_vel_event(igor, ts, hx, hy): - """ - Event handler when d-pad is pressed. - This event handler will set the velocity of the wrists. - - :param igor: (bound parameter) - :param ts: (ignored) - :param hx: - :param hy: - :return: - """ +# ------------------------------------------------------------------------------ +# Wrist Event Handlers +# +# Note: There are different event handlers depending on the type of controller +# ------------------------------------------------------------------------------ + + +def wrist_vel_event__buttons(igor, scale, ts, value): l_arm = igor.left_arm r_arm = igor.right_arm - if hy == 0: + if value: + l_arm.set_wrist_velocity(scale) + r_arm.set_wrist_velocity(scale) + else: l_arm.set_wrist_velocity(0.0) r_arm.set_wrist_velocity(0.0) - else: - joy_low_pass = 0.95 - vel = (joy_low_pass*l_arm.wrist_velocity)+hy*(1.0-joy_low_pass)*0.25 - l_arm.set_wrist_velocity(vel) - r_arm.set_wrist_velocity(vel) + + +def wrist_vel_event__axis(igor, deadzone_calc, ts, value): + l_arm = igor.left_arm + r_arm = igor.right_arm + vel = deadzone_calc(value) + l_arm.set_wrist_velocity(vel) + r_arm.set_wrist_velocity(vel) # ------------------------------------------------------------------------------ -# Chassis Event Handlers +# Stance Handlers # ------------------------------------------------------------------------------ -def chassis_velocity_event(igor, in_deadzone_func, ts, axis_value): - """ - Event handler when right stick Y-Axis motion occurs. - - :param igor: (bound parameter) - :param in_deadzone_func: (bound parameter) - :param ts: (ignored) - :param axis_value: [-1,1] value of the axis - """ - chassis = igor.chassis - if in_deadzone_func(axis_value): - chassis.set_directional_velocity(0.0) - else: - joy_scale = -0.5 - dead_zone = igor.joystick_dead_zone - value = joy_scale*(axis_value-(dead_zone*math_utils.sign(axis_value))) - chassis.set_directional_velocity(value) +def stance_height_triggers_event(igor, igor_state, vel_calc, ts, value): + # Ignore this if soft shutdown is currently being requested + if igor_state.soft_shutdown_enabled: + return + val = vel_calc(value) + igor.left_leg.set_knee_velocity(val) + igor.right_leg.set_knee_velocity(val) -def chassis_yaw_event(igor, in_deadzone_func, ts, axis_value): - """ - Event handler when right stick X-Axis motion occurs. - :param igor: (bound parameter) - :param in_deadzone_func: (bound parameter) - :param ts: (ignored) - :param axis_value: [-1,1] value of the axis - """ - chassis = igor.chassis - if in_deadzone_func(axis_value): - chassis.set_yaw_velocity(0.0) +def soft_shutdown_event(igor, igor_state, ts, pressed): + if pressed: + igor_state.soft_shutdown_enabled = True + # The Leg class has a software position limit which will set actual velocity to 0 if getting near the safety limits + igor.left_leg.set_knee_velocity(1.0) + igor.right_leg.set_knee_velocity(1.0) else: - scale = 25.0 - dead_zone = igor.joystick_dead_zone - wheel_radius = igor.wheel_radius - wheel_base = igor.wheel_base - value = (scale * wheel_radius / wheel_base) * (axis_value - dead_zone * math_utils.sign(axis_value)) - chassis.set_yaw_velocity(value) + igor_state.soft_shutdown_enabled = False + + igor.allow_transition_to_idle(pressed) # ------------------------------------------------------------------------------ -# Misc Event Handlers +# Chassis Event Handlers # ------------------------------------------------------------------------------ -def stance_height_triggers_event(igor, joy, vel_calc, ts, axis_value): - """ - - :param igor: - :param joy: - :param vel_calc: - :param ts: - :param axis_value: - """ - # Ignore this if `OPTIONS` is pressed - if joy.get_button('OPTIONS'): - return +def chassis_velocity_event(igor, vel_calc, ts, value): + igor.chassis.set_directional_velocity(vel_calc(value)) - val = vel_calc() - igor.left_leg.set_knee_velocity(val) - igor.right_leg.set_knee_velocity(val) +def chassis_yaw_event(igor, vel_calc, ts, value): + igor.chassis.set_yaw_velocity(vel_calc(value)) -def stance_height_event(igor, vel_calc, ts, pressed): - """ - Event handler when `OPTIONS` button is pressed or released. - :param igor: (bound parameter) - :param vel_calc: (bound parameter) - :param ts: - :param pressed: - """ - if pressed: - igor.left_leg.set_knee_velocity(1.0) - igor.right_leg.set_knee_velocity(1.0) - if igor.left_leg.knee_angle > 2.5: - # TODO: implement restart - pass - #igor.request_restart() - #igor.request_stop() - else: - val = vel_calc() - igor.left_leg.set_knee_velocity(val) - igor.right_leg.set_knee_velocity(val) +# ------------------------------------------------------------------------------ +# Misc Event Handlers +# ------------------------------------------------------------------------------ def balance_controller_event(igor, ts, pressed): """ - Event handler when `TOUCHPAD` button is pressed or released. + Event handler to a request to temporarily disable/enable the balance controller. + + Note: It is *highly* recommended to only use this when somebody is physically + close enough to the robot to balance it manually. Otherwise, your robot will fall + and potentially cause damage to itself or its surroundings! :param igor: :param ts: :param pressed: """ + pressed = bool(pressed) igor.set_balance_controller_state(not pressed) def quit_session_event(igor, ts, pressed): """ - Event handler when `SHARE` button is pressed or released. - When the button is pressed, - and the robot is ready (in the "started" state), + Event handler to react to the "quit" button being pressed or released. + When the button is pressed, and the robot is ready (in the "started" state), the session will begin to quit. + Note: Like the balance controller toggler, it is *highly* recommended to only + request the session to quit when somebody is able to stabilize the robot + during the shutdown procedure, to ensure that it "crouches" without falling + over or hitting anything! + :param igor: :param ts: :param pressed: @@ -244,30 +192,26 @@ def quit_session_event(igor, ts, pressed): # ------------------------------------------------------------------------------ -# Helper Functions +# Binding event handler parameters # ------------------------------------------------------------------------------ -def set_arm_vel_z(arm, val): - """ - Set the Z axis velocity of the given arm. - If the velocity is less than 1e-4, this function does nothing. - - :param arm: - :param val: The velocity - """ - # Ignore small values from being set (noise) - if abs(val) > 1e-4: - arm.set_z_velocity(val) +def deadzone_clip(igor): + def calculate(val): + if abs(val) <= igor.joystick_dead_zone: + return 0.0 + else: + return val + return calculate -def both_triggers_released(joy): - """ - :return: ``True`` if both the left and right triggers are not being pressed - """ - left = joy.get_button('LEFT_TRIGGER') - right = joy.get_button('RIGHT_TRIGGER') - return not (left or right) +def deadzone_clip_scaled(igor, dz_scale, out_scale): + def calculate(val): + if abs(val) <= igor.joystick_dead_zone * dz_scale: + return 0.0 + else: + return val * out_scale + return calculate # ------------------------------------------------------------------------------ @@ -275,113 +219,76 @@ def both_triggers_released(joy): # ------------------------------------------------------------------------------ -def register_igor_event_handlers(igor): - """ - Registers all Igor joystick event handlers - """ - - joystick = igor.joystick - - # ---------------------------------------------- - # Functions to be passed to event handlers below - - arm_x_deadzone = lambda val: abs(val) <= igor.joystick_dead_zone*3.0 - arm_y_deadzone = lambda val: abs(val) <= igor.joystick_dead_zone - - def stance_height_calc(): - l_val = joystick.get_axis('LEFT_TRIGGER') - r_val = joystick.get_axis('RIGHT_TRIGGER') - d_ax = l_val-r_val - if abs(d_ax) > igor.joystick_dead_zone: - return 0.5*d_ax - return 0.0 +class IgorControlState(object): - # The current joystick used is not a global state, so we need to wrap it here - both_triggers = lambda: both_triggers_released(joystick) + __slots__ = ('_balance_controller_enabled', '_soft_shutdown_enabled') + def __init__(self): + self._balance_controller_enabled = True + self._soft_shutdown_enabled = False - # ---------------------------------------------------------------------- - # Functions which have bound parameters, in order to have right function - # signature for event handlers + @property + def soft_shutdown_enabled(self): + return self._soft_shutdown_enabled + + @soft_shutdown_enabled.setter + def soft_shutdown_enabled(self, value): + self._soft_shutdown_enabled = value - # ------------ - # Quit Session - quit_session = funpart(quit_session_event, igor) - joystick.add_button_event_handler('SHARE', quit_session) +def _add_event_handlers(igor, controller, controller_mapping): - # --------------- - # Toggle Balancer + # Shortcut closure to get around having to use functool.partial + def bind_to_method(method, *args): + def bound_meth(ts, val): + method(*args, ts, val) + return bound_meth - balance_controller = funpart(balance_controller_event, igor) - joystick.add_button_event_handler('TOUCHPAD', balance_controller) + arm_vel_calc = deadzone_clip_scaled(igor, 1.0, 0.5) + chassis_vel_calc = deadzone_clip_scaled(igor, 1.0, 0.4) + chassis_yaw_calc = deadzone_clip_scaled(igor, 1.0, 25.0 * igor.wheel_radius / igor.wheel_base) + igor_state = IgorControlState() - # ----------------------- - # Left Arm event handlers + controller.add_button_event_handler(controller_mapping.quit, bind_to_method(quit_session_event, igor)) + controller.add_button_event_handler(controller_mapping.balance_controller_toggle, bind_to_method(balance_controller_event, igor)) - # Reacts to left stick Y-axis - arm_x_vel = funpart(arm_x_vel_event, igor, arm_x_deadzone) - joystick.add_axis_event_handler('LEFT_STICK_Y', arm_x_vel) + controller.add_axis_event_handler(controller_mapping.arm_vel_x, bind_to_method(arm_x_vel_event, igor, arm_vel_calc)) + controller.add_axis_event_handler(controller_mapping.arm_vel_y, bind_to_method(arm_y_vel_event, igor, arm_vel_calc)) + controller.add_button_event_handler(controller_mapping.lower_arm, bind_to_method(arm_z_vel_lower_event, igor, controller_mapping.raise_arm)) + controller.add_button_event_handler(controller_mapping.raise_arm, bind_to_method(arm_z_vel_raise_event, igor, controller_mapping.lower_arm)) - # Reacts to left stick X-axis - arm_y_vel = funpart(arm_y_vel_event, igor, arm_y_deadzone) - joystick.add_axis_event_handler('LEFT_STICK_X', arm_y_vel) + controller.add_axis_event_handler(controller_mapping.chassis_vel, bind_to_method(chassis_velocity_event, igor, chassis_vel_calc)) + controller.add_axis_event_handler(controller_mapping.chassis_yaw, bind_to_method(chassis_yaw_event, igor, chassis_yaw_calc)) - # Reacts to left trigger axis - arm_z_vel_lt = funpart(arm_z_vel_event_l, igor) - joystick.add_axis_event_handler('LEFT_TRIGGER', arm_z_vel_lt) + controller.add_button_event_handler(controller_mapping.soft_shutdown, bind_to_method(soft_shutdown_event, igor, igor_state)) - # Reacts to right trigger axis - arm_z_vel_rt = funpart(arm_z_vel_event_r, igor) - joystick.add_axis_event_handler('RIGHT_TRIGGER', arm_z_vel_rt) + # Stance height events are responded to differently by different kinds of controllers, thus requiring a bit more complex logic + if controller_mapping.stance_height_control_strategy == 'TRIGGERS': + stance_height_lower_axis_id = controller_mapping.stance_height[0] + stance_height_raise_axis_id = controller_mapping.stance_height[1] - # ------------------------ - # Both Arms event handlers + lower_event = bind_to_method(stance_height_triggers_event, igor, igor_state, deadzone_clip_scaled(igor, 5.0, 1.0)) + raise_event = bind_to_method(stance_height_triggers_event, igor, igor_state, deadzone_clip_scaled(igor, 5.0, -1.0)) - # Reacts to triggers pressed/released - zero_arm_z = funpart(zero_arm_z_event, igor, both_triggers) - joystick.add_button_event_handler('LEFT_TRIGGER', zero_arm_z) - joystick.add_button_event_handler('RIGHT_TRIGGER', zero_arm_z) + controller.add_axis_event_handler(stance_height_lower_axis_id, lower_event) + controller.add_axis_event_handler(stance_height_raise_axis_id, raise_event) + elif controller_mapping.stance_height_control_strategy == 'SLIDER': + stance_height_axis_id = controller_mapping.stance_height + controller.add_axis_event_handler(stance_height_axis_id, bind_to_method(stance_height_triggers_event, igor, igor_state, deadzone_clip_scaled(igor, 5.0, -1.0))) - # Reacts to D-Pad pressed/released - wrist_vel = funpart(wrist_vel_event, igor) - #joystick.add_dpad_event_handler(wrist_vel) + # Like stance height events, wrist velocity events have the same conditional logic + if controller_mapping.wrist_velocity_control_strategy == 'BUTTONS': + wrist_vel_lower_btn_id = controller_mapping.wrist_vel[0] + wrist_vel_raise_btn_id = controller_mapping.wrist_vel[1] + controller.add_button_event_handler(wrist_vel_lower_btn_id, bind_to_method(wrist_vel_event__buttons, igor, -0.5)) + controller.add_button_event_handler(wrist_vel_raise_btn_id, bind_to_method(wrist_vel_event__buttons, igor, 0.5)) + elif controller_mapping.wrist_velocity_control_strategy == 'SLIDER': + wrist_vel_axis_id = controller_mapping.wrist_vel + wrist_vel_event = bind_to_method(wrist_vel_event__axis, igor, deadzone_clip(igor)) + controller.add_axis_event_handler(wrist_vel_axis_id, wrist_vel_event) - # ---------------------- - # Chassis event handlers - # Reacts to right stick Y-axis - chassis_velocity = funpart(chassis_velocity_event, igor, arm_y_deadzone) - joystick.add_axis_event_handler('RIGHT_STICK_Y', chassis_velocity) - - # Reacts to right stick X-axis - chassis_yaw = funpart(chassis_yaw_event, igor, arm_y_deadzone) - joystick.add_axis_event_handler('RIGHT_STICK_X', chassis_yaw) - - # ------------- - # Stance height - - stance_height_trigger = funpart(stance_height_triggers_event, igor, joystick, stance_height_calc) - joystick.add_axis_event_handler('LEFT_TRIGGER', stance_height_trigger) - joystick.add_axis_event_handler('RIGHT_TRIGGER', stance_height_trigger) - - stance_height = funpart(stance_height_event, igor, stance_height_calc) - joystick.add_button_event_handler('OPTIONS', stance_height) - - # ------------------------------ - # Camera specific event handlers - - if igor.has_camera: - # Implement your own functionality here - def c_set_cam(ts, pressed): - pass - def sq_set_cam(ts, pressed): - pass - def t_set_cam(ts, pressed): - pass - def x_set_cam(ts, pressed): - pass - - joystick.add_button_event_handler('CIRCLE', c_set_cam) - joystick.add_button_event_handler('SQUARE', sq_set_cam) - joystick.add_button_event_handler('TRIANGLE', t_set_cam) - joystick.add_button_event_handler('X', x_set_cam) +def register_igor_event_handlers(igor): + """ + Registers all Igor joystick event handlers + """ + _add_event_handlers(igor, igor.joystick, igor.config.controller_mapping) diff --git a/kits/igor2/components/leg.py b/kits/igor2/components/leg.py index 1467f3b..dee4a92 100644 --- a/kits/igor2/components/leg.py +++ b/kits/igor2/components/leg.py @@ -188,3 +188,11 @@ def set_knee_velocity(self, vel): self.acquire_value_lock() self._user_commanded_knee_velocity = vel self.release_value_lock() + + def reset_state(self): + super(Leg, self).reset_state() + + self._knee_velocity = 0 + self._user_commanded_knee_velocity = 0 + self._e_term.fill(0) + self._current_cmd_tip_fk.fill(0) diff --git a/kits/igor2/igor2_demo.py b/kits/igor2/igor2_demo.py index 8e6cf26..667c757 100644 --- a/kits/igor2/igor2_demo.py +++ b/kits/igor2/igor2_demo.py @@ -5,10 +5,61 @@ root_path = os.path.abspath(os.path.join(os.path.dirname(__file__), '..', '..')) sys.path = [root_path] + sys.path +# ------------------------------------------------------------------------------ +# Configuration +# ------------------------------------------------------------------------------ + +import argparse +parser = argparse.ArgumentParser() +parser.add_argument('--imitation', action='store_true', default=False, dest='imitation', + help='Use the imitation group API to not connect to physical modules on the network.') +parser.add_argument('--joystick', action='store_true', default=False, dest='joystick', help='Drive Igor using a USB gamecontroller.') +parser.add_argument('--mobile-io', action='store_true', default=True, dest='mobile_io', help='(ignored)') +parser.add_argument('--mobile-io-frequency', default=200.0, dest='mobile_io_freq', + help='Feedback frequency of Mobile IO group. Ignored if not controlling Igor using a Mobile IO device.') +parser.add_argument('--mobile-io-family', type=str, default=None, dest='mobile_io_family', + help='The Mobile IO app family.') +parser.add_argument('--mobile-io-name', type=str, default=None, dest='mobile_io_name', + help='The Mobile IO app name.') + +args = parser.parse_args() + +# TODO: Move into encapsulating function +io_fam = args.mobile_io_family +io_name = args.mobile_io_name +has_io_fam = io_fam is not None +has_io_name = io_name is not None +has_io = not args.joystick + +if has_io: + if not has_io_fam: + # Mobile IO default family + io_fam = 'HEBI' + if not has_io_name: + # Mobile IO default name + io_name = 'Mobile IO' + +from components.configuration import Igor2Config +igor_config = Igor2Config(args.imitation) + +if has_io: + from math import isfinite + if args.mobile_io_freq < 1.0 or not isfinite(args.mobile_io_freq): + print('ignoring specified Mobile IO feedback frequency {0}. Defaulting to 200Hz.'.format(args.mobile_io_freq)) + fbk_freq = 200.0 + else: + fbk_freq = args.mobile_io_freq + + igor_config.select_controller_by_mobile_io(io_fam, io_name, fbk_freq) + + +# ------------------------------------------------------------------------------ +# Running +# ------------------------------------------------------------------------------ from components.igor import Igor -igor = Igor() +igor = Igor(config=igor_config) keep_running = True def stop_running_callback(*args): @@ -16,12 +67,14 @@ def stop_running_callback(*args): keep_running = False +igor.add_on_stop_callback(stop_running_callback) igor.start() # The joystick has been initialized once `igor.start()` returns joy = igor.joystick if joy is None: - raise RuntimeError('No Joystick found') + igor.request_stop() + raise RuntimeError('Could not initialize controller for Igor.') from time import sleep while keep_running: diff --git a/kits/igor2/install/hebi-demo.service b/kits/igor2/install/hebi-demo.service new file mode 100644 index 0000000..20ae4fc --- /dev/null +++ b/kits/igor2/install/hebi-demo.service @@ -0,0 +1,15 @@ +[Unit] +Description=HEBI Demo +Requires=network.target +After=multi-user.target + +[Service] +Type=simple +WorkingDirectory=/home/hebi +ExecStart=/home/hebi/launch_demo +StartLimitInterval=0 +User=hebi +StandardOutput=syslog + +[Install] +WantedBy=multi-user.target diff --git a/kits/igor2/install/hebi_demo_wait_for_connected b/kits/igor2/install/hebi_demo_wait_for_connected new file mode 100644 index 0000000..aff7b53 --- /dev/null +++ b/kits/igor2/install/hebi_demo_wait_for_connected @@ -0,0 +1,26 @@ +#!/usr/bin/env bash + +# Change this to the network interface connected to the subnet containing the modules of your robot. +DEPLOY_IFACE=eno1 + +# Wait for connection to come up, if it is not already +IF_ATTRS=$(ip a show $DEPLOY_IFACE 2>/dev/null | head -n1 | awk '{ print substr($3, 2, length($3)-2) }' | tr ',' ' ') +iface_up=$(echo $IF_ATTRS | grep -e "[[:space:]]UP[[:space:]]" | wc -l) + +if [ $iface_up != 0 ]; then + # Interface is up - we can exit + exit 0; +fi + +while [ 1 ]; do + echo "Waiting for network interface '$DEPLOY_IFACE' to come up..." + sleep 3 + + IF_ATTRS=$(ip a show $DEPLOY_IFACE 2>/dev/null | head -n1 | awk '{ print substr($3, 2, length($3)-2) }' | tr ',' ' ') + iface_up=$(echo $IF_ATTRS | grep -e "[[:space:]]UP[[:space:]]" | wc -l) + + if [ $iface_up != 0 ]; then + # Interface is up - we can exit + exit 0; + fi +done diff --git a/kits/igor2/install/launch_demo b/kits/igor2/install/launch_demo new file mode 100644 index 0000000..26aed7f --- /dev/null +++ b/kits/igor2/install/launch_demo @@ -0,0 +1,4 @@ +#!/usr/bin/env bash + +./hebi_demo_wait_for_connected +python3 ./hebi-python-examples/kits/igor2/igor2_demo.py diff --git a/kits/igor2/resources/mobile_io_igor.png b/kits/igor2/resources/mobile_io_igor.png new file mode 100644 index 0000000..0d753e2 Binary files /dev/null and b/kits/igor2/resources/mobile_io_igor.png differ diff --git a/kits/igor2/resources/ps4_igor.png b/kits/igor2/resources/ps4_igor.png new file mode 100644 index 0000000..8a40999 Binary files /dev/null and b/kits/igor2/resources/ps4_igor.png differ diff --git a/util/input/_joystick_mapping.py b/util/input/_joystick_mapping.py new file mode 100644 index 0000000..9240dfd --- /dev/null +++ b/util/input/_joystick_mapping.py @@ -0,0 +1,123 @@ +from sdl2 import * + +_default_axis_map = dict() +_default_button_map = dict() + +# ------------------------------------------------------------------------------ +# Axes +# ------------------------------------------------------------------------------ + +# LEFTX +_default_axis_map['LEFT_STICK_X'] = SDL_CONTROLLER_AXIS_LEFTX + +# LEFTY +_default_axis_map['LEFT_STICK_Y'] = SDL_CONTROLLER_AXIS_LEFTY + +# RIGHTX +_default_axis_map['RIGHT_STICK_X'] = SDL_CONTROLLER_AXIS_RIGHTX + +# RIGHTY +_default_axis_map['RIGHT_STICK_Y'] = SDL_CONTROLLER_AXIS_RIGHTY + +# TRIGGERLEFT +_default_axis_map['LEFT_TRIGGER'] = SDL_CONTROLLER_AXIS_TRIGGERLEFT +_default_axis_map['TRIGGER_LEFT'] = SDL_CONTROLLER_AXIS_TRIGGERLEFT +_default_axis_map['L2'] = SDL_CONTROLLER_AXIS_TRIGGERLEFT + +# TRIGGERRIGHT +_default_axis_map['RIGHT_TRIGGER'] = SDL_CONTROLLER_AXIS_TRIGGERRIGHT +_default_axis_map['TRIGGER_RIGHT'] = SDL_CONTROLLER_AXIS_TRIGGERRIGHT +_default_axis_map['R2'] = SDL_CONTROLLER_AXIS_TRIGGERRIGHT + +# ------------------------------------------------------------------------------ +# Buttons +# ------------------------------------------------------------------------------ + +# A +_default_button_map['A'] = SDL_CONTROLLER_BUTTON_A +_default_button_map['CROSS'] = SDL_CONTROLLER_BUTTON_A + +# B +_default_button_map['B'] = SDL_CONTROLLER_BUTTON_B +_default_button_map['CIRCLE'] = SDL_CONTROLLER_BUTTON_B + +# X +_default_button_map['X'] = SDL_CONTROLLER_BUTTON_X +_default_button_map['SQUARE'] = SDL_CONTROLLER_BUTTON_X + +# Y +_default_button_map['Y'] = SDL_CONTROLLER_BUTTON_Y +_default_button_map['TRIANGLE'] = SDL_CONTROLLER_BUTTON_Y + +# BACK +_default_button_map['BACK'] = SDL_CONTROLLER_BUTTON_BACK +_default_button_map['SELECT'] = SDL_CONTROLLER_BUTTON_BACK +_default_button_map['SHARE'] = SDL_CONTROLLER_BUTTON_BACK + +# GUIDE +# Note - the guide button does not exist on all controllers. +# For example, Some Xbox controllers do not have one. Consequently, this shouldn't be used for required events. +_default_button_map['GUIDE'] = SDL_CONTROLLER_BUTTON_GUIDE +_default_button_map['TOUCHPAD'] = SDL_CONTROLLER_BUTTON_GUIDE + +# START +_default_button_map['START'] = SDL_CONTROLLER_BUTTON_START +_default_button_map['OPTIONS'] = SDL_CONTROLLER_BUTTON_START + +# LEFTSTICK +_default_button_map['LEFT_STICK'] = SDL_CONTROLLER_BUTTON_LEFTSTICK +_default_button_map['L3'] = SDL_CONTROLLER_BUTTON_LEFTSTICK + +# RIGHTSTICK +_default_button_map['RIGHT_STICK'] = SDL_CONTROLLER_BUTTON_RIGHTSTICK +_default_button_map['R3'] = SDL_CONTROLLER_BUTTON_RIGHTSTICK + +# LEFTSHOULDER +_default_button_map['LEFT_SHOULDER'] = SDL_CONTROLLER_BUTTON_LEFTSHOULDER +_default_button_map['L1'] = SDL_CONTROLLER_BUTTON_LEFTSHOULDER + +# RIGHTSHOULDER +_default_button_map['RIGHT_SHOULDER'] = SDL_CONTROLLER_BUTTON_RIGHTSHOULDER +_default_button_map['R1'] = SDL_CONTROLLER_BUTTON_RIGHTSHOULDER + +# DPAD_UP +_default_button_map['DPAD_UP'] = SDL_CONTROLLER_BUTTON_DPAD_UP +_default_button_map['UP'] = SDL_CONTROLLER_BUTTON_DPAD_UP + +# DPAD_DOWN +_default_button_map['DPAD_DOWN'] = SDL_CONTROLLER_BUTTON_DPAD_DOWN +_default_button_map['DOWN'] = SDL_CONTROLLER_BUTTON_DPAD_DOWN + +# DPAD_LEFT +_default_button_map['DPAD_LEFT'] = SDL_CONTROLLER_BUTTON_DPAD_LEFT +_default_button_map['LEFT'] = SDL_CONTROLLER_BUTTON_DPAD_LEFT + +# DPAD_RIGHT +_default_button_map['DPAD_RIGHT'] = SDL_CONTROLLER_BUTTON_DPAD_RIGHT +_default_button_map['RIGHT'] = SDL_CONTROLLER_BUTTON_DPAD_RIGHT + + +class JoystickMapping(object): + """Maps string axis and button names to their SDL2 values""" + __slots__ = ('__axis_map', '__button_map') + + def __init__(self, a_map, b_map): + self.__axis_map = a_map + self.__button_map = b_map + + def get_axis(self, axis): + if axis not in self.__axis_map: + raise ValueError('Invalid axis {0}'.format(axis)) + return self.__axis_map[axis] + + def get_button(self, button): + if button not in self.__button_map: + raise ValueError('Invalid button {0}'.format(button)) + return self.__button_map[button] + + +_default_mapping = JoystickMapping(_default_axis_map, _default_button_map) + + +def default_joystick_mapping(): + return _default_mapping diff --git a/util/input/_joystick_mappings.py b/util/input/_joystick_mappings.py deleted file mode 100644 index 0144618..0000000 --- a/util/input/_joystick_mappings.py +++ /dev/null @@ -1,287 +0,0 @@ -import sys -from ..type_utils import assert_type - - -# ------------------------------------------------------------------------------ -# Classes -# ------------------------------------------------------------------------------ - - -class JoystickMappingEntry(object): - - def __call__(self): - return self.__func() - - def __init__(self, type_, index, name, mapper): - self.__type = type_ - self.__index = index - self.__name = name - - if type_ == 'Axis': - self.__func = lambda: mapper.joystick.get_axis(index) - elif type_ == 'Button': - self.__func = lambda: mapper.joystick.get_button(index) - else: - raise ValueError('Unknown type "{0}"'.format(type_)) - - @property - def type(self): - """ - :rtype: str - """ - return self.__type - - @property - def index(self): - """ - :rtype: int - """ - return self.__index - - @property - def name(self): - """ - :return: Human readable name of this entry - :rtype: str - """ - return self.__name - - -class JoystickMapper(object): - - def __get_axis(self, name): - return self.__axes[name] - - def __get_button(self, name): - return self.__buttons[name] - - def __get_string(self, item): - assert_type(item, str, 'key') - if item.startswith('AXIS_'): - return self.__get_axis(item[5:]) - elif item.startswith('BUTTON_'): - return self.__get_button(item[7:]) - raise KeyError('Key {0} not found'.format(item)) - - def __getitem__(self, item): - """ - :type item: str - """ - return self.__get_string(item) - - def __init__(self, joystick): - self.__joy = joystick - self.__axes = dict() - self.__buttons = dict() - self.__axis_ids = set() - self.__button_ids = set() - - @property - def axis_ids(self): - """ - :rtype: list - """ - return self.__axis_ids[:] - - @property - def button_ids(self): - """ - :rtype: list - """ - return self.__button_ids[:] - - @property - def joystick(self): - """ - :rtype: .Joystick.Joystick - """ - return self.__joy - - def add_axis(self, index, name, key): - """ - :param index: Index of the axis - :type index: int - :param name: Human readable representation of the axis - :type name: str - :param key: Key of this axis - :type key: str - """ - entry = JoystickMappingEntry('Axis', index, name, self) - self.__axes[key] = entry - self.__axes[index] = entry - self.__axis_ids.add('AXIS_' + key.upper()) - - def add_button(self, index, name, key, analogues=None): - """ - :param index: Index of the button - :type index: int - :param name: Human readable representation of the button - :type name: str - :param key: Key of this button - :type key: str - :param analogues: List of potential analogues. For example, `SELECT` (PS3) is an analog to `SHARE` (PS4) - """ - entry = JoystickMappingEntry('Button', index, name, self) - self.__buttons[key] = entry - self.__buttons[index] = entry - self.__button_ids.add('BUTTON_' + key.upper()) - - if analogues is not None: - for analog in analogues: - self.__buttons[analog] = entry - self.__button_ids.add('BUTTON_' + analog.upper()) - - def get_axis(self, axis): - """ - :param axis: Index of the axis - :type axis: int, str - - :rtype: .JoystickMappingEntry - """ - if type(axis) == int: - if axis in self.__axes: - return self.__axes[axis] - raise IndexError('Axis[{0}] is out of range') - elif type(axis) == str: - axiskey = axis.upper() - if axiskey in self.__axes: - return self.__axes[axiskey] - raise KeyError('Axis["{0}"] not found'.format(axis)) - raise TypeError(type(axis)) - - def get_axis_value(self, axis): - return self.get_axis(axis)() - - def get_button(self, button): - """ - :param button: - :type button: int, str - - :rtype: .JoystickMappingEntry - """ - - if type(button) == int: - if button in self.__buttons: - return self.__buttons[button] - raise IndexError('Button[{0}] is out of range') - elif type(button) == str: - buttonkey = button.upper() - if buttonkey in self.__buttons: - return self.__buttons[buttonkey] - raise KeyError('Button["{0}"] not found'.format(button)) - raise TypeError(type(button)) - - def get_button_value(self, button): - return self.get_button(button)() - - -# ------------------------------------------------------------------------------ -# Mapping functions -# ------------------------------------------------------------------------------ - - -def __map_ps3_cechzc2u(joystick): - """ - Proper controller mapping for Sony Playstation 3 Wireless Controller - Model CECHZC2U - """ - # TODO: test on OSX and Windows - d = JoystickMapper(joystick) - - d.add_axis(0, 'Left Stick (x)', 'LEFT_STICK_X') - d.add_axis(1, 'Left Stick (y)', 'LEFT_STICK_Y') - d.add_axis(3, 'Right Stick (x)', 'RIGHT_STICK_X') - d.add_axis(4, 'Right Stick (y)', 'RIGHT_STICK_Y') - d.add_axis(2, 'Left Trigger', 'LEFT_TRIGGER') - d.add_axis(5, 'Right Trigger', 'RIGHT_TRIGGER') - - d.add_button(0, 'X', 'X') - d.add_button(1, 'Circle', 'CIRCLE') - d.add_button(2, 'Triangle', 'TRIANGLE') - d.add_button(3, 'Square', 'SQUARE') - d.add_button(4, 'Left Shoulder', 'LEFT_SHOULDER') - d.add_button(5, 'Right Shoulder', 'RIGHT_SHOULDER') - d.add_button(6, 'Left Trigger', 'LEFT_TRIGGER') - d.add_button(7, 'Right Trigger', 'RIGHT_TRIGGER') - d.add_button(8, 'Select', 'SELECT', ['SHARE']) - d.add_button(9, 'Start', 'START', ['OPTIONS']) - d.add_button(10, 'Home', 'HOME', ['TOUCHPAD']) - d.add_button(11, 'Left Stick', 'LEFT_STICK') - d.add_button(12, 'Right Stick', 'RIGHT_STICK') - d.add_button(13, 'DPad Up', 'DPAD_UP') - d.add_button(14, 'DPad Down', 'DPAD_DOWN') - d.add_button(15, 'DPad Left', 'DPAD_LEFT') - d.add_button(16, 'DPad Right', 'DPAD_RIGHT') - return d - - -def __map_ps4_cuh_zct2u(joystick): - """ - Proper controller mapping for Sony Playstation 4 Wireless Controller - Model CUH-ZXT2U - - """ - d = JoystickMapper(joystick) - - d.add_axis(0, 'Left Stick (x)', 'LEFT_STICK_X') - d.add_axis(1, 'Left Stick (y)', 'LEFT_STICK_Y') - - d.add_button(4, 'Left Shoulder', 'LEFT_SHOULDER') - d.add_button(5, 'Right Shoulder', 'RIGHT_SHOULDER') - d.add_button(9, 'Options', 'OPTIONS', ['START']) - d.add_button(8, 'Share', 'SHARE', ['SELECT']) - - if sys.platform == 'darwin' or sys.platform == 'win32': - d.add_axis(3, 'Left Trigger', 'LEFT_TRIGGER') - d.add_axis(4, 'Right Trigger', 'RIGHT_TRIGGER') - d.add_axis(2, 'Right Stick (x)', 'RIGHT_STICK_X') - d.add_axis(5, 'Right Stick (y)', 'RIGHT_STICK_Y') - - d.add_button(1, 'X', 'X') - d.add_button(2, 'Circle', 'CIRCLE') - d.add_button(3, 'Triangle', 'TRIANGLE') - d.add_button(0, 'Square', 'SQUARE') - d.add_button(6, 'Left Trigger', 'LEFT_TRIGGER') - d.add_button(7, 'Right Trigger', 'RIGHT_TRIGGER') - d.add_button(10, 'Left Stick', 'LEFT_STICK') - d.add_button(11, 'Right Stick', 'RIGHT_STICK') - d.add_button(13, 'Touchpad', 'TOUCHPAD', ['HOME']) - elif sys.platform.startswith('linux'): - d.add_axis(2, 'Left Trigger', 'LEFT_TRIGGER') - d.add_axis(5, 'Right Trigger', 'RIGHT_TRIGGER') - d.add_axis(3, 'Right Stick (x)', 'RIGHT_STICK_X') - d.add_axis(4, 'Right Stick (y)', 'RIGHT_STICK_Y') - - d.add_button(0, 'X', 'X') - d.add_button(1, 'Circle', 'CIRCLE') - d.add_button(2, 'Triangle', 'TRIANGLE') - d.add_button(3, 'Square', 'SQUARE') - d.add_button(6, 'Left Trigger', 'LEFT_TRIGGER') - d.add_button(7, 'Right Trigger', 'RIGHT_TRIGGER') - d.add_button(11, 'Left Stick', 'LEFT_STICK') - d.add_button(12, 'Right Stick', 'RIGHT_STICK') - d.add_button(10, 'Touchpad', 'TOUCHPAD', ['HOME']) - else: - raise RuntimeError('Unknown Operating System/Platform {0}'.format(sys.platform)) - return d - - -__mappings = { - '030000004c0500006802000000000000': __map_ps3_cechzc2u, - '030000004c0500006802000011810000': __map_ps3_cechzc2u, - '030000004c050000cc09000011010000': __map_ps4_cuh_zct2u, - '030000004c050000cc09000011810000': __map_ps4_cuh_zct2u, - '030000004c050000a00b000011810000': __map_ps4_cuh_zct2u, -} - - -# ------------------------------------------------------------------------------ -# Public API -# ------------------------------------------------------------------------------ - - -def get_joystick_mapping(joystick): - guid = joystick.guid - if guid in __mappings: - return __mappings[guid](joystick) - return None diff --git a/util/input/event_handler.py b/util/input/event_handler.py index 1080da9..2056bb0 100644 --- a/util/input/event_handler.py +++ b/util/input/event_handler.py @@ -8,41 +8,37 @@ class SDLEventHandler(object): __sdl_event_attr_dict = { - SDL_JOYAXISMOTION : "jaxis", - SDL_JOYBALLMOTION : "jball", - SDL_JOYHATMOTION : "jhat", - SDL_JOYBUTTONDOWN : "jbutton", - SDL_JOYBUTTONUP : "jbutton", - SDL_JOYDEVICEADDED : "jdevice", - SDL_JOYDEVICEREMOVED : "jdevice"} + SDL_CONTROLLERAXISMOTION : "caxis", + SDL_CONTROLLERBUTTONDOWN : "cbutton", + SDL_CONTROLLERBUTTONUP : "cbutton", + SDL_CONTROLLERDEVICEADDED : "cdevice", + SDL_CONTROLLERDEVICEREMOVED : "cdevice", + SDL_CONTROLLERDEVICEREMAPPED : "cdevice"} def __init__(self): hooks = dict() - hooks[SDL_JOYAXISMOTION] = [_joystick_axis_motion] - hooks[SDL_JOYBALLMOTION] = [_joystick_ball_motion] - hooks[SDL_JOYHATMOTION] = [_joystick_hat_motion] - hooks[SDL_JOYBUTTONDOWN] = [_joystick_button_event] - hooks[SDL_JOYBUTTONUP] = [_joystick_button_event] - hooks[SDL_JOYDEVICEADDED] = [_joystick_added] - hooks[SDL_JOYDEVICEREMOVED] = [] + hooks[SDL_CONTROLLERAXISMOTION] = [_joystick_axis_motion] + hooks[SDL_CONTROLLERBUTTONDOWN] = [_joystick_button_event] + hooks[SDL_CONTROLLERBUTTONUP] = [_joystick_button_event] + hooks[SDL_CONTROLLERDEVICEADDED] = [_joystick_added] + hooks[SDL_CONTROLLERDEVICEREMOVED] = [_joystick_removed] self.__event_hooks = hooks self.__loop_mutex = threading.Lock() self.__last_event_loop_time = 0.0 - self.__event_loop_frequency = 250.0 # Limit event loop to 250 Hz self.__event_loop_period = 1.0/self.__event_loop_frequency - self.__thread = None - def __on_event(self, event, data): - data = getattr(data, SDLEventHandler.__sdl_event_attr_dict[event]) + def __dispatch_event(self, sdl_event): + event = sdl_event.type + if event not in SDLEventHandler.__sdl_event_attr_dict: + return + + data = getattr(sdl_event, SDLEventHandler.__sdl_event_attr_dict[event]) for entry in self.__event_hooks[event]: entry(data) - def __dispatch_event(self, sdl_event): - self.__on_event(sdl_event.type, sdl_event) - def __run(self): while True: last_time = self.__last_event_loop_time @@ -91,14 +87,14 @@ def start(self): from . import joystick as JoystickModule -from .joystick import Joystick +from .joystick import Joystick as JoystickController import sdl2.ext.compat def _joystick_added(sdl_event): joystick_id = sdl_event.which try: - joystick = Joystick(joystick_id) + joystick = JoystickController(joystick_id) JoystickModule._joysticks[joystick_id] = joystick except Exception as e: import sdl2.ext.compat @@ -106,29 +102,21 @@ def _joystick_added(sdl_event): print('Could not add Joystick "{0}"'.format(sdl2.ext.compat.stringify(SDL_JoystickNameForIndex(joystick_id), 'utf8'))) -def _joystick_axis_motion(sdl_event): - joystick_id = sdl_event.which - ts = sdl_event.timestamp - axis = sdl_event.axis - value = sdl_event.value - Joystick.at_index(joystick_id)._on_axis_motion(ts, axis, value) - - -def _joystick_ball_motion(sdl_event): +def _joystick_removed(sdl_event): joystick_id = sdl_event.which - ts = sdl_event.timestamp - ball = sdl_event.ball - xrel = sdl_event.xrel - yrel = sdl_event.yrel - Joystick.at_index(joystick_id)._on_ball_motion(ts, ball, xrel, yrel) + try: + import sdl2.ext.compat + print("Warning: joystick {0} was removed".format(sdl2.ext.compat.stringify(SDL_JoystickNameForIndex(joystick_id), 'utf8'))) + finally: + pass -def _joystick_hat_motion(sdl_event): +def _joystick_axis_motion(sdl_event): joystick_id = sdl_event.which ts = sdl_event.timestamp - hat = sdl_event.hat + axis = sdl_event.axis value = sdl_event.value - Joystick.at_index(joystick_id)._on_hat_motion(ts, hat, value) + JoystickController.at_index(joystick_id)._on_axis_motion(ts, axis, value) def _joystick_button_event(sdl_event): @@ -136,7 +124,7 @@ def _joystick_button_event(sdl_event): ts = sdl_event.timestamp button = sdl_event.button value = sdl_event.state - Joystick.at_index(joystick_id)._on_button_event(ts, button, value) + JoystickController.at_index(joystick_id)._on_button_event(ts, button, value) _singleton = SDLEventHandler() diff --git a/util/input/joystick.py b/util/input/joystick.py index 422310d..0f21fcb 100644 --- a/util/input/joystick.py +++ b/util/input/joystick.py @@ -2,9 +2,7 @@ from threading import Lock, Condition from ..type_utils import assert_callable, assert_type, assert_prange -SDL_InitSubSystem(SDL_INIT_JOYSTICK) -SDL_InitSubSystem(SDL_INIT_GAMECONTROLLER) -SDL_InitSubSystem(SDL_INIT_HAPTIC) +SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_GAMECONTROLLER | SDL_INIT_HAPTIC) SDL_JoystickEventState(SDL_ENABLE) SDL_SetHint(SDL_HINT_JOYSTICK_ALLOW_BACKGROUND_EVENTS, b"1") @@ -35,13 +33,15 @@ class JoystickEvent(object): Additionally, this acts as a condition variable, providing mutual exclusion to this event. """ + __slots__ = ('__callbacks', '__cv') + def __init__(self): self.__callbacks = set() self.__cv = Condition(Lock()) - def __call__(self, *args): + def __call__(self, ts, val): for callback in self.__callbacks: - callback(*args) + callback(ts, val) def add_event_handler(self, callback): """ @@ -68,52 +68,26 @@ class JoystickEventsMap(object): Map used to encapsulate all events for a joystick """ - def __init__(self, num_axes, num_balls, num_hats, num_buttons): - - d = dict() - d[AXIS] = [None] * num_axes - for i in range(num_axes): - d[AXIS][i] = JoystickEvent() + __slots__ = ('_axis_events', '_button_events') - d[BALL] = [None] * num_balls - for i in range(num_balls): - d[BALL][i] = JoystickEvent() + def __init__(self, num_axes, num_buttons): + axis_events = [None] * num_axes + button_events = [None] * num_buttons - d[HAT] = [None] * num_hats - for i in range(num_hats): - d[HAT][i] = JoystickEvent() + for i in range(num_axes): + axis_events[i] = JoystickEvent() - d[BUTTON] = [None] * num_buttons for i in range(num_buttons): - d[BUTTON][i] = JoystickEvent() + button_events[i] = JoystickEvent() - self.__dict = d + self._axis_events = axis_events + self._button_events = button_events - def get_event(self, key, index): - """ - :param key: - :type key: int - :param index: - :type index: int + def get_axis_event(self, index): + return self._axis_events[index] - :rtype: JoystickEvent - """ - assert_type(index, int, 'index') - assert_type(key, int, 'key') - if not key in self.__dict: - raise KeyError('{0} is not an event type'.format(key)) - events = self.__dict[key] - assert_prange(index, len(events)) - return events[index] - - def __getitem__(self, item): - """ - Calls :meth:`get_event` with the given input - :param item: tuple of key and index - :type item: tuple - """ - assert_type(item, tuple, 'item') - return self.get_event(*item) + def get_button_event(self, index): + return self._button_events[index] class GameControllerException(RuntimeError): @@ -126,31 +100,9 @@ def __init__(self, *args, **kwargs): # ------------------------------------------------------------------------------ -def hat_get_val(value): - hx = 0 - hy = 0 - if value & SDL_HAT_UP: - hy = 1 - elif value & SDL_HAT_DOWN: - hy = -1 - if value & SDL_HAT_RIGHT: - hx = 1 - elif value & SDL_HAT_LEFT: - hx = -1 - return hx, hy - - -AXIS = 1 -BALL = 2 -HAT = 3 -BUTTON = 4 - _joysticks = dict() -_val_mapper = { - AXIS: lambda value: value*0.0000305185, - BALL: lambda xrel, yrel: (xrel, yrel), - HAT: hat_get_val, - BUTTON: lambda value: value == SDL_PRESSED} +_axis_val_cvt = lambda value: value*0.0000305185 +_button_val_cvt = lambda value: value != 0 # ------------------------------------------------------------------------------ @@ -167,150 +119,89 @@ class Joystick(object): This class wraps the SDL2 library. """ + # TODO + #__slots__ = [] + def __init__(self, index): self.__gamepad = SDL_GameControllerOpen(index) if not self.__gamepad: - self.__joystick = None - self._as_parameter_ = self.__joystick raise GameControllerException('Not a game controller') self.__joystick = SDL_JoystickOpen(index) self.__index = index - self._as_parameter_ = self.__joystick - self.__initialize() + self._as_parameter_ = self.__gamepad + + # See details at https://wiki.libsdl.org/SDL_GameControllerAxis + num_axes = 6 + # See details at https://wiki.libsdl.org/SDL_GameControllerButton + num_buttons = 15 + self.__initialize_values(num_axes, num_buttons) - from ._joystick_mappings import get_joystick_mapping - self.__joystick_mapping = get_joystick_mapping(self) + from ._joystick_mapping import default_joystick_mapping + self.__joystick_mapping = default_joystick_mapping() def __del__(self): - if (self.__gamepad): + if self.__gamepad: SDL_GameControllerClose(self.__gamepad) - if (self.__joystick): + if self.__joystick: SDL_JoystickClose(self.__joystick) - def __getattr__(self, item): - """ - Hack to allow user to get button or axis value as a field of the Joystick - For example, if there was a button named 'SHARE', one could do the following: - - joy = get_joystick() # this is the Joystick object - pressed = joy.BUTTON_SHARE - print('is SHARE button pressed? {0}'.format(pressed)) - - This is only called if an attribute (field in layman's terms) is not found - in a call to __getattribute__ - """ - if item == '__joystick_mapping': - raise RuntimeError - elif self.__joystick_mapping is None: - raise AttributeError - elif item.startswith('BUTTON_') or item.startswith('AXIS_'): - return self.__joystick_mapping[item]() - else: - raise AttributeError - - def __dir__(self): - """ - Hack to allow IDE's and Python consoles to autocomplete button and axis names - """ - s_dir = set() - for entry in super(Joystick, self).__dir__(): - s_dir.add(entry) - - if self.__joystick_mapping is not None: - s_dir = s_dir.union(self.__joystick_mapping.axis_ids) - s_dir = s_dir.union(self.__joystick_mapping.button_ids) - return [entry for entry in s_dir] - - def __initialize(self): + def __initialize_values(self, num_axes, num_buttons): + self.__events = JoystickEventsMap(num_axes, num_buttons) + from ctypes import byref, c_int - num_axes = SDL_JoystickNumAxes(self) - num_balls = SDL_JoystickNumBalls(self) - num_hats = SDL_JoystickNumHats(self) - num_buttons = SDL_JoystickNumButtons(self) + last_axis_vals = [None] * num_axes + for i in range(num_axes): + last_axis_vals[i] = _axis_val_cvt(SDL_GameControllerGetAxis(self, i)) + + last_button_vals = [None] * num_buttons + for i in range(num_buttons): + last_button_vals[i] = _button_val_cvt(SDL_GameControllerGetButton(self, i)) - self.__num_axes = num_axes - self.__num_balls = num_balls - self.__num_hats = num_hats - self.__num_buttons = num_buttons - self.__events = JoystickEventsMap(num_axes, num_balls, num_hats, num_buttons) + self.__last_axis_vals = last_axis_vals + self.__last_button_vals = last_button_vals - from ctypes import byref, c_int + def __get_next_axis_val(self, idx, timeout): + event = self.__events.get_axis_event(idx) + event.acquire() + event.wait(timeout) + value = self.__last_axis_vals[idx] + event.release() + return value - if num_axes > 0: - axes_last_val = [None] * num_axes - for i in range(num_axes): - axes_last_val[i] = _val_mapper[AXIS](SDL_JoystickGetAxis(self, i)) - else: - axes_last_val = [] - - if num_balls > 0: - balls_last_val = [None] * num_balls - xrel = c_int() - yrel = c_int() - for i in range(num_balls): - SDL_JoystickGetBall(self, i, byref(xrel), byref(yrel)) - balls_last_val[i] = _val_mapper[BALL](xrel.value, yrel.value) - else: - balls_last_val = [] - - if num_hats > 0: - hats_last_val = [None] * num_hats - for i in range(num_hats): - hats_last_val[i] = _val_mapper[HAT](SDL_JoystickGetHat(self, i)) - else: - hats_last_val = [] - - if num_buttons > 0: - buttons_last_val = [None] * num_buttons - for i in range(num_buttons): - buttons_last_val[i] = _val_mapper[BUTTON](SDL_JoystickGetButton(self, i)) - else: - buttons_last_val = [] - - last_vals = { - AXIS: axes_last_val, - BALL: balls_last_val, - HAT: hats_last_val, - BUTTON: buttons_last_val } - self.__last_vals = last_vals - - def __get_next_val(self, key, idx, timeout): - event = self.__events[key, idx] + def __get_next_button_val(self, idx, timeout): + event = self.__events.get_button_event(idx) event.acquire() event.wait(timeout) - val = self.__last_vals[key][idx] + value = self.__last_button_vals[idx] event.release() - return val + return value - def __update_last_val(self, idx, key, *args): - cvtr = _val_mapper[key] - value = cvtr(*args) - event = self.__events[key, idx] + def __update_last_axis_val(self, idx, val): + value = _axis_val_cvt(val) + event = self.__events.get_axis_event(idx) event.acquire() - self.__last_vals[key][idx] = value + self.__last_axis_vals[idx] = value event.notify_all() event.release() return event, value - def __register_event_handler(self, idx, key, callback): - self.__events[key, idx].add_event_handler(callback) + def __update_last_button_val(self, idx, val): + value = _button_val_cvt(val) + event = self.__events.get_button_event(idx) + event.acquire() + self.__last_button_vals[idx] = value + event.notify_all() + event.release() + return event, value def _on_axis_motion(self, ts, axis, value): - event, val = self.__update_last_val(axis, AXIS, value) + event, val = self.__update_last_axis_val(axis, value) event(ts, val) - def _on_ball_motion(self, ts, ball, xrel, yrel): - event, val = self.__update_last_val(ball, BALL, xrel, yrel) - event(ts, *val) - - def _on_hat_motion(self, ts, hat, value): - event, val = self.__update_last_val(hat, HAT, value) - event(ts, *val) - def _on_button_event(self, ts, button, value): - event, val = self.__update_last_val(button, BUTTON, value) + event, val = self.__update_last_button_val(button, value) event(ts, val) @staticmethod @@ -369,7 +260,7 @@ def name(self): :rtype: str """ import sdl2.ext.compat - return sdl2.ext.compat.stringify(SDL_GameControllerName(self.__gamepad), 'utf8') + return sdl2.ext.compat.stringify(SDL_GameControllerName(self), 'utf8') @property def guid(self): @@ -377,15 +268,11 @@ def guid(self): :return: the GUID of the device this joystick represents :rtype: str """ - return SDL_JoystickGetGUIDString(SDL_JoystickGetGUID(self)) + return SDL_JoystickGetGUIDString(SDL_JoystickGetGUID(self.__joystick)) - def add_dpad_event_handler(self, handler): - """ - :param handler: - :return: - """ - assert_callable(handler) - self.__register_event_handler(0, HAT, handler) + @property + def controller_type(self): + return 'GameController' def add_axis_event_handler(self, axis, handler): """ @@ -401,9 +288,9 @@ def add_axis_event_handler(self, axis, handler): """ assert_callable(handler) if type(axis) == str: - axis = self.__joystick_mapping.get_axis(axis).index + axis = self.__joystick_mapping.get_axis(axis) assert_type(axis, int, 'axis') - self.__register_event_handler(axis, AXIS, handler) + self.__events.get_axis_event(axis).add_event_handler(handler) def add_button_event_handler(self, button, handler): """ @@ -419,26 +306,9 @@ def add_button_event_handler(self, button, handler): """ assert_callable(handler) if type(button) == str: - button = self.__joystick_mapping.get_button(button).index + button = self.__joystick_mapping.get_button(button) assert_type(button, int, 'button') - self.__register_event_handler(button, BUTTON, handler) - - def get_button_name(self, index): - """ - Get the name of the button at the given index. If this joystick has no - mapping, then an exception will be thrown. - - :param index: The index of the button - :type index: int - :return: The human readable name of the button - :rtype: str - :raises GameControllerException: If the joystick does not have a mapping - :raises TypeError: If `index` is not an int - """ - assert_type(index, int, 'index') - if self.__joystick_mapping is None: - raise GameControllerException('Joystick has no mapping') - return self.__joystick_mapping.get_button(index).name + self.__events.get_button_event(button).add_event_handler(handler) def get_axis(self, axis): """ @@ -455,49 +325,8 @@ def get_axis(self, axis): :raises IndexError: If `axis` is an invalid index """ if type(axis) == str: - if self.__joystick_mapping is not None: - return self.__joystick_mapping.get_axis_value(axis) - else: - raise GameControllerException('Joystick has no mapping. You must retrieve button values by integer index') - assert_type(axis, int, 'axis') - vals = self.__last_vals[AXIS] - assert_prange(axis, len(vals), 'axis index') - return vals[axis] - - def get_ball(self, ball): - """ - Retrieves the last value of the ball at the given index. - This call does not block. - - :return: - :rtype: tuple - - :raises TypeError: If `ball` is not an int - :raises IndexError: If `ball` is an invalid index - """ - assert_type(ball, int, 'ball') - vals = self.__last_vals[BALL] - assert_prange(ball, len(vals), 'ball index') - return vals[ball] - - def get_hat(self, hat): - """ - Retrieves the last value of the hat at the given index. - This call does not block. - - :param hat: The index of the hat - :type button: int - - :return: - :rtype: tuple - - :raises TypeError: If `hat` is not an int - :raises IndexError: If `hat` is an invalid index - """ - assert_type(hat, int, 'hat') - vals = self.__last_vals[HAT] - assert_prange(hat, len(vals), 'hat index') - return vals[hat] + axis = self.__joystick_mapping.get_axis(axis) + return self.__last_axis_vals[axis] def get_button(self, button): """ @@ -516,19 +345,13 @@ def get_button(self, button): :raises IndexError: If `button` is an invalid (int) index """ if type(button) == str: - if self.__joystick_mapping is not None: - return self.__joystick_mapping.get_button_value(button) - else: - raise GameControllerException('Joystick has no mapping. You must retrieve button values by integer index') - assert_type(button, int, 'button') - vals = self.__last_vals[BUTTON] - assert_prange(button, len(vals), 'button index') - return vals[button] + button = self.__joystick_mapping.get_button(button) + return self.__last_button_vals[button] def get_next_axis_state(self, axis, timeout=None): """ Retrieves the next value of the given axis. This call blocks until - an sdl2.SDL_JOYAXISMOTION event has been received for the axis + an sdl2. event has been received for the axis :param axis: :type axis: int, str @@ -537,38 +360,14 @@ def get_next_axis_state(self, axis, timeout=None): :raises TypeError: If `axis` is not an int or str :raises IndexError: If `axis` is an invalid index """ - return self.__get_next_val(AXIS, axis, timeout) - - def get_next_ball_state(self, ball, timeout=None): - """ - Retrieves the next value of the given ball. This call blocks until - an sdl2.SDL_JOYBALLMOTION event has been received for the ball - - :param ball: - :type ball: int - - :raises TypeError: If `ball` is not an int - :raises IndexError: If `ball` is an invalid index - """ - return self.__get_next_val(BALL, ball, timeout) - - def get_next_hat_state(self, hat, timeout=None): - """ - Retrieves the next value of the given hat. This call blocks until - an sdl2.SDL_JOYHATMOTION event has been received for the hat - - :param hat: - :type hat: int - - :raises TypeError: If `hat` is not an int - :raises IndexError: If `hat` is an invalid index - """ - return self.__get_next_val(HAT, hat, timeout) + if type(axis) == str: + axis = self.__joystick_mapping.get_axis(axis) + return self.__get_next_axis_val(axis, timeout) def get_next_button_state(self, button, timeout=None): """ Retrieves the next value of the given button. This call blocks until - an sdl2.SDL_JOYBUTTONDOWN or sdl2.SDL_JOYBUTTONUP event has been received + an sdl2.