001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package org.wpilib.driverstation;
006
007import java.util.EnumSet;
008import java.util.HashMap;
009import java.util.Map;
010import org.wpilib.driverstation.internal.DriverStationBackend;
011import org.wpilib.event.BooleanEvent;
012import org.wpilib.event.EventLoop;
013import org.wpilib.hardware.hal.DriverStationJNI;
014import org.wpilib.math.util.Pair;
015
016/**
017 * Handle input from standard HID devices connected to the Driver Station.
018 *
019 * <p>This class handles standard input that comes from the Driver Station. Each time a value is
020 * requested the most recent value is returned. There is a single class instance for each device and
021 * the mapping of ports to hardware buttons depends on the code in the Driver Station.
022 */
023public class GenericHID {
024  /** Represents a rumble output on the Joystick. */
025  public enum RumbleType {
026    /** Left rumble motor. */
027    LEFT_RUMBLE,
028    /** Right rumble motor. */
029    RIGHT_RUMBLE,
030    /** Left trigger rumble motor. */
031    LEFT_TRIGGER_RUMBLE,
032    /** Right trigger rumble motor. */
033    RIGHT_TRIGGER_RUMBLE,
034  }
035
036  /** Represents the various outputs that a HID may support. */
037  public enum SupportedOutput {
038    /// No outputs supported.
039    NONE(0x0),
040    /// Mono LED support.
041    MONO_LED(0x1),
042    /// RGB LED support.
043    RGB_LED(0x2),
044    /// Player LED support.
045    PLAYER_LED(0x4),
046    /// Rumble support.
047    RUMBLE(0x8),
048    /// Trigger rumble support.
049    TRIGGER_RUMBLE(0x10);
050
051    private final int value;
052
053    SupportedOutput(int value) {
054      this.value = value;
055    }
056
057    /**
058     * Get the bitfield value of this SupportedOutput.
059     *
060     * @return the bitfield value of this SupportedOutput.
061     */
062    public int getValue() {
063      return value;
064    }
065  }
066
067  /** USB HID interface type. */
068  public enum HIDType {
069    /** Unknown. */
070    UNKNOWN(0),
071    /** Standard. */
072    STANDARD(1),
073    /** Xbox 360. */
074    XBOX_360(2),
075    /** Xbox One. */
076    XBOX_ONE(3),
077    /** PS3. */
078    PS3(4),
079    /** PS4. */
080    PS4(5),
081    /** PS5. */
082    PS5(6),
083    /** Switch Pro. */
084    SWITCH_PRO(7),
085    /** Switch Joycon Left. */
086    SWITCH_JOYCON_LEFT(8),
087    /** Switch Joycon Right. */
088    SWITCH_JOYCON_RIGHT(9),
089    /** Switch Joycon Pair. */
090    SWITCH_JOYCON_PAIR(10);
091
092    /** HIDType value. */
093    public final int value;
094
095    private static final Map<Integer, HIDType> map = new HashMap<>();
096
097    HIDType(int value) {
098      this.value = value;
099    }
100
101    static {
102      for (HIDType hidType : HIDType.values()) {
103        map.put(hidType.value, hidType);
104      }
105    }
106
107    /**
108     * Creates an HIDType with the given value.
109     *
110     * @param value HIDType's value.
111     * @return HIDType with the given value.
112     */
113    public static HIDType of(int value) {
114      return map.get(value);
115    }
116  }
117
118  private final int m_port;
119  private int m_leftRumble;
120  private int m_rightRumble;
121  private int m_leftTriggerRumble;
122  private int m_rightTriggerRumble;
123  private final Map<EventLoop, Map<Integer, BooleanEvent>> m_buttonCache = new HashMap<>();
124  private final Map<EventLoop, Map<Pair<Integer, Double>, BooleanEvent>> m_axisLessThanCache =
125      new HashMap<>();
126  private final Map<EventLoop, Map<Pair<Integer, Double>, BooleanEvent>> m_axisGreaterThanCache =
127      new HashMap<>();
128  private final Map<EventLoop, Map<Integer, BooleanEvent>> m_povCache = new HashMap<>();
129
130  /**
131   * Construct an instance of a device.
132   *
133   * @param port The port index on the Driver Station that the device is plugged into.
134   */
135  public GenericHID(int port) {
136    m_port = port;
137  }
138
139  /**
140   * Get the button value (starting at button 1).
141   *
142   * <p>The buttons are returned in a single 16 bit value with one bit representing the state of
143   * each button. The appropriate button is returned as a boolean value.
144   *
145   * <p>This method returns true if the button is being held down at the time that this method is
146   * being called.
147   *
148   * @param button The button number to be read (starting at 1)
149   * @return The state of the button.
150   */
151  public boolean getRawButton(int button) {
152    return DriverStationBackend.getStickButton(m_port, (byte) button);
153  }
154
155  /**
156   * Whether the button was pressed since the last check. Button indexes begin at 1.
157   *
158   * <p>This method returns true if the button went from not pressed to held down since the last
159   * time this method was called. This is useful if you only want to call a function once when you
160   * press the button.
161   *
162   * @param button The button index, beginning at 0.
163   * @return Whether the button was pressed since the last check.
164   */
165  public boolean getRawButtonPressed(int button) {
166    return DriverStationBackend.getStickButtonPressed(m_port, (byte) button);
167  }
168
169  /**
170   * Whether the button was released since the last check. Button indexes begin at 1.
171   *
172   * <p>This method returns true if the button went from held down to not pressed since the last
173   * time this method was called. This is useful if you only want to call a function once when you
174   * release the button.
175   *
176   * @param button The button index, beginning at 0.
177   * @return Whether the button was released since the last check.
178   */
179  public boolean getRawButtonReleased(int button) {
180    return DriverStationBackend.getStickButtonReleased(m_port, button);
181  }
182
183  /**
184   * Constructs an event instance around this button's digital signal.
185   *
186   * @param button the button index
187   * @param loop the event loop instance to attach the event to.
188   * @return an event instance representing the button's digital signal attached to the given loop.
189   */
190  public BooleanEvent button(int button, EventLoop loop) {
191    synchronized (m_buttonCache) {
192      var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>());
193      return cache.computeIfAbsent(button, k -> new BooleanEvent(loop, () -> getRawButton(k)));
194    }
195  }
196
197  /**
198   * Get the value of the axis.
199   *
200   * @param axis The axis to read, starting at 0.
201   * @return The value of the axis.
202   */
203  public double getRawAxis(int axis) {
204    return DriverStationBackend.getStickAxis(m_port, axis);
205  }
206
207  /**
208   * Get the angle of a POV on the HID.
209   *
210   * @param pov The index of the POV to read (starting at 0). Defaults to 0.
211   * @return the angle of the POV.
212   */
213  public POVDirection getPOV(int pov) {
214    return DriverStationBackend.getStickPOV(m_port, pov);
215  }
216
217  /**
218   * Get the angle of the default POV (index 0) on the HID.
219   *
220   * @return the angle of the POV.
221   */
222  public POVDirection getPOV() {
223    return getPOV(0);
224  }
225
226  /**
227   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
228   *
229   * @param angle POV angle.
230   * @param loop the event loop instance to attach the event to.
231   * @return a BooleanEvent instance based around this angle of a POV on the HID.
232   */
233  public BooleanEvent pov(POVDirection angle, EventLoop loop) {
234    return pov(0, angle, loop);
235  }
236
237  /**
238   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
239   *
240   * @param pov index of the POV to read (starting at 0). Defaults to 0.
241   * @param angle POV angle.
242   * @param loop the event loop instance to attach the event to.
243   * @return a BooleanEvent instance based around this angle of a POV on the HID.
244   */
245  public BooleanEvent pov(int pov, POVDirection angle, EventLoop loop) {
246    synchronized (m_povCache) {
247      var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>());
248      // angle.value is a 4 bit bitfield
249      return cache.computeIfAbsent(
250          pov * 16 + angle.value, k -> new BooleanEvent(loop, () -> getPOV(pov) == angle));
251    }
252  }
253
254  /**
255   * Constructs a BooleanEvent instance based around the up direction of the default (index 0) POV
256   * on the HID.
257   *
258   * @param loop the event loop instance to attach the event to.
259   * @return a BooleanEvent instance based around the up direction a POV on the HID.
260   */
261  public BooleanEvent povUp(EventLoop loop) {
262    return pov(POVDirection.UP, loop);
263  }
264
265  /**
266   * Constructs a BooleanEvent instance based around the up right direction of the default (index 0)
267   * POV on the HID.
268   *
269   * @param loop the event loop instance to attach the event to.
270   * @return a BooleanEvent instance based around the up right direction of a POV on the HID.
271   */
272  public BooleanEvent povUpRight(EventLoop loop) {
273    return pov(POVDirection.UP_RIGHT, loop);
274  }
275
276  /**
277   * Constructs a BooleanEvent instance based around the right direction of the default (index 0)
278   * POV on the HID.
279   *
280   * @param loop the event loop instance to attach the event to.
281   * @return a BooleanEvent instance based around the right direction of a POV on the HID.
282   */
283  public BooleanEvent povRight(EventLoop loop) {
284    return pov(POVDirection.RIGHT, loop);
285  }
286
287  /**
288   * Constructs a BooleanEvent instance based around the down right direction of the default (index
289   * 0) POV on the HID.
290   *
291   * @param loop the event loop instance to attach the event to.
292   * @return a BooleanEvent instance based around the down right direction of a POV on the HID.
293   */
294  public BooleanEvent povDownRight(EventLoop loop) {
295    return pov(POVDirection.DOWN_RIGHT, loop);
296  }
297
298  /**
299   * Constructs a BooleanEvent instance based around the down direction of the default (index 0) POV
300   * on the HID.
301   *
302   * @param loop the event loop instance to attach the event to.
303   * @return a BooleanEvent instance based around the down direction of a POV on the HID.
304   */
305  public BooleanEvent povDown(EventLoop loop) {
306    return pov(POVDirection.DOWN, loop);
307  }
308
309  /**
310   * Constructs a BooleanEvent instance based around the down left direction of the default (index
311   * 0) POV on the HID.
312   *
313   * @param loop the event loop instance to attach the event to.
314   * @return a BooleanEvent instance based around the down left direction of a POV on the HID.
315   */
316  public BooleanEvent povDownLeft(EventLoop loop) {
317    return pov(POVDirection.DOWN_LEFT, loop);
318  }
319
320  /**
321   * Constructs a BooleanEvent instance based around the left direction of the default (index 0) POV
322   * on the HID.
323   *
324   * @param loop the event loop instance to attach the event to.
325   * @return a BooleanEvent instance based around the left direction of a POV on the HID.
326   */
327  public BooleanEvent povLeft(EventLoop loop) {
328    return pov(POVDirection.LEFT, loop);
329  }
330
331  /**
332   * Constructs a BooleanEvent instance based around the up left direction of the default (index 0)
333   * POV on the HID.
334   *
335   * @param loop the event loop instance to attach the event to.
336   * @return a BooleanEvent instance based around the up left direction of a POV on the HID.
337   */
338  public BooleanEvent povUpLeft(EventLoop loop) {
339    return pov(POVDirection.UP_LEFT, loop);
340  }
341
342  /**
343   * Constructs a BooleanEvent instance based around the center (not pressed) of the default (index
344   * 0) POV on the HID.
345   *
346   * @param loop the event loop instance to attach the event to.
347   * @return a BooleanEvent instance based around the center of a POV on the HID.
348   */
349  public BooleanEvent povCenter(EventLoop loop) {
350    return pov(POVDirection.CENTER, loop);
351  }
352
353  /**
354   * Constructs an event instance that is true when the axis value is less than {@code threshold},
355   * attached to the given loop.
356   *
357   * @param axis The axis to read, starting at 0
358   * @param threshold The value below which this event should return true.
359   * @param loop the event loop instance to attach the event to.
360   * @return an event instance that is true when the axis value is less than the provided threshold.
361   */
362  public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
363    synchronized (m_axisLessThanCache) {
364      var cache = m_axisLessThanCache.computeIfAbsent(loop, k -> new HashMap<>());
365      return cache.computeIfAbsent(
366          Pair.of(axis, threshold),
367          k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold));
368    }
369  }
370
371  /**
372   * Constructs an event instance that is true when the axis value is greater than {@code
373   * threshold}, attached to the given loop.
374   *
375   * @param axis The axis to read, starting at 0
376   * @param threshold The value above which this event should return true.
377   * @param loop the event loop instance to attach the event to.
378   * @return an event instance that is true when the axis value is greater than the provided
379   *     threshold.
380   */
381  public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) {
382    synchronized (m_axisGreaterThanCache) {
383      var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>());
384      return cache.computeIfAbsent(
385          Pair.of(axis, threshold),
386          k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold));
387    }
388  }
389
390  /**
391   * Get the maximum axis index for the joystick.
392   *
393   * @return the maximum axis index for the joystick
394   */
395  public int getAxesMaximumIndex() {
396    return DriverStationBackend.getStickAxesMaximumIndex(m_port);
397  }
398
399  /**
400   * Get the number of axes for the HID.
401   *
402   * @return the number of axis for the current HID
403   */
404  public int getAxesAvailable() {
405    return DriverStationBackend.getStickAxesAvailable(m_port);
406  }
407
408  /**
409   * Get the maximum POV index for the joystick.
410   *
411   * @return the maximum POV index for the joystick
412   */
413  public int getPOVsMaximumIndex() {
414    return DriverStationBackend.getStickPOVsMaximumIndex(m_port);
415  }
416
417  /**
418   * For the current HID, return the number of POVs.
419   *
420   * @return the number of POVs for the current HID
421   */
422  public int getPOVsAvailable() {
423    return DriverStationBackend.getStickPOVsAvailable(m_port);
424  }
425
426  /**
427   * Get the maximum button index for the joystick.
428   *
429   * @return the maximum button index for the joystick
430   */
431  public int getButtonsMaximumIndex() {
432    return DriverStationBackend.getStickButtonsMaximumIndex(m_port);
433  }
434
435  /**
436   * For the current HID, return the number of buttons.
437   *
438   * @return the number of buttons for the current HID
439   */
440  public long getButtonsAvailable() {
441    return DriverStationBackend.getStickButtonsAvailable(m_port);
442  }
443
444  /**
445   * Get if the HID is connected.
446   *
447   * @return true if the HID is connected
448   */
449  public boolean isConnected() {
450    return DriverStationBackend.isJoystickConnected(m_port);
451  }
452
453  /**
454   * Get the type of the HID.
455   *
456   * @return the type of the HID.
457   */
458  public HIDType getGamepadType() {
459    return HIDType.of(DriverStationBackend.getJoystickGamepadType(m_port));
460  }
461
462  /**
463   * Get the supported outputs for the HID.
464   *
465   * @return the supported outputs for the HID.
466   */
467  public EnumSet<SupportedOutput> getSupportedOutputs() {
468    int supported = DriverStationBackend.getJoystickSupportedOutputs(m_port);
469    EnumSet<SupportedOutput> outputs = EnumSet.noneOf(SupportedOutput.class);
470    for (SupportedOutput output : SupportedOutput.values()) {
471      if ((supported & output.getValue()) != 0) {
472        outputs.add(output);
473      }
474    }
475    return outputs;
476  }
477
478  /**
479   * Get the name of the HID.
480   *
481   * @return the name of the HID.
482   */
483  public String getName() {
484    return DriverStationBackend.getJoystickName(m_port);
485  }
486
487  /**
488   * Get the port number of the HID.
489   *
490   * @return The port number of the HID.
491   */
492  public int getPort() {
493    return m_port;
494  }
495
496  /**
497   * Set leds on the controller. If only mono is supported, the system will use the highest value
498   * passed in.
499   *
500   * @param r Red value from 0-255
501   * @param g Green value from 0-255
502   * @param b Blue value from 0-255
503   */
504  public void setLeds(int r, int g, int b) {
505    int value = ((r & 0xFF) << 16) | ((g & 0xFF) << 8) | (b & 0xFF);
506    DriverStationJNI.setJoystickLeds((byte) m_port, value);
507  }
508
509  /**
510   * Set the rumble output for the HID. The DS currently supports 4 rumble values: left rumble,
511   * right rumble, left trigger rumble, and right trigger rumble.
512   *
513   * @param type Which rumble value to set
514   * @param value The normalized value (0 to 1) to set the rumble to
515   */
516  public void setRumble(RumbleType type, double value) {
517    value = Math.clamp(value, 0, 1);
518    int rumbleValue = (int) (value * 65535);
519    switch (type) {
520      case LEFT_RUMBLE -> this.m_leftRumble = rumbleValue;
521      case RIGHT_RUMBLE -> this.m_rightRumble = rumbleValue;
522      case LEFT_TRIGGER_RUMBLE -> this.m_leftTriggerRumble = rumbleValue;
523      case RIGHT_TRIGGER_RUMBLE -> this.m_rightTriggerRumble = rumbleValue;
524      default -> {
525        // no-op
526      }
527    }
528
529    DriverStationJNI.setJoystickRumble(
530        (byte) this.m_port,
531        this.m_leftRumble,
532        this.m_rightRumble,
533        this.m_leftTriggerRumble,
534        this.m_rightTriggerRumble);
535  }
536
537  /**
538   * Check if a touchpad finger is available.
539   *
540   * @param touchpad The touchpad to check.
541   * @param finger The finger to check.
542   * @return true if the touchpad finger is available.
543   */
544  public boolean getTouchpadFingerAvailable(int touchpad, int finger) {
545    return DriverStationBackend.getStickTouchpadFingerAvailable(m_port, touchpad, finger);
546  }
547
548  /**
549   * Get the touchpad finger data.
550   *
551   * @param touchpad The touchpad to read.
552   * @param finger The finger to read.
553   * @return The touchpad finger data.
554   */
555  public TouchpadFinger getTouchpadFinger(int touchpad, int finger) {
556    return DriverStationBackend.getStickTouchpadFinger(m_port, touchpad, finger);
557  }
558}