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 edu.wpi.first.wpilibj;
006
007import edu.wpi.first.hal.DriverStationJNI;
008import edu.wpi.first.math.MathUtil;
009import edu.wpi.first.wpilibj.event.BooleanEvent;
010import edu.wpi.first.wpilibj.event.EventLoop;
011import java.util.HashMap;
012import java.util.Map;
013
014/**
015 * Handle input from standard HID devices connected to the Driver Station.
016 *
017 * <p>This class handles standard input that comes from the Driver Station. Each time a value is
018 * requested the most recent value is returned. There is a single class instance for each device and
019 * the mapping of ports to hardware buttons depends on the code in the Driver Station.
020 */
021public class GenericHID {
022  /** Represents a rumble output on the JoyStick. */
023  public enum RumbleType {
024    kLeftRumble,
025    kRightRumble,
026    kBothRumble
027  }
028
029  public enum HIDType {
030    kUnknown(-1),
031    kXInputUnknown(0),
032    kXInputGamepad(1),
033    kXInputWheel(2),
034    kXInputArcadeStick(3),
035    kXInputFlightStick(4),
036    kXInputDancePad(5),
037    kXInputGuitar(6),
038    kXInputGuitar2(7),
039    kXInputDrumKit(8),
040    kXInputGuitar3(11),
041    kXInputArcadePad(19),
042    kHIDJoystick(20),
043    kHIDGamepad(21),
044    kHIDDriving(22),
045    kHIDFlight(23),
046    kHID1stPerson(24);
047
048    public final int value;
049
050    @SuppressWarnings("PMD.UseConcurrentHashMap")
051    private static final Map<Integer, HIDType> map = new HashMap<>();
052
053    HIDType(int value) {
054      this.value = value;
055    }
056
057    static {
058      for (HIDType hidType : HIDType.values()) {
059        map.put(hidType.value, hidType);
060      }
061    }
062
063    public static HIDType of(int value) {
064      return map.get(value);
065    }
066  }
067
068  private final int m_port;
069  private int m_outputs;
070  private short m_leftRumble;
071  private short m_rightRumble;
072
073  /**
074   * Construct an instance of a device.
075   *
076   * @param port The port index on the Driver Station that the device is plugged into.
077   */
078  public GenericHID(int port) {
079    m_port = port;
080  }
081
082  /**
083   * Get the button value (starting at button 1).
084   *
085   * <p>The buttons are returned in a single 16 bit value with one bit representing the state of
086   * each button. The appropriate button is returned as a boolean value.
087   *
088   * <p>This method returns true if the button is being held down at the time that this method is
089   * being called.
090   *
091   * @param button The button number to be read (starting at 1)
092   * @return The state of the button.
093   */
094  public boolean getRawButton(int button) {
095    return DriverStation.getStickButton(m_port, (byte) button);
096  }
097
098  /**
099   * Whether the button was pressed since the last check. Button indexes begin at 1.
100   *
101   * <p>This method returns true if the button went from not pressed to held down since the last
102   * time this method was called. This is useful if you only want to call a function once when you
103   * press the button.
104   *
105   * @param button The button index, beginning at 1.
106   * @return Whether the button was pressed since the last check.
107   */
108  public boolean getRawButtonPressed(int button) {
109    return DriverStation.getStickButtonPressed(m_port, (byte) button);
110  }
111
112  /**
113   * Whether the button was released since the last check. Button indexes begin at 1.
114   *
115   * <p>This method returns true if the button went from held down to not pressed since the last
116   * time this method was called. This is useful if you only want to call a function once when you
117   * release the button.
118   *
119   * @param button The button index, beginning at 1.
120   * @return Whether the button was released since the last check.
121   */
122  public boolean getRawButtonReleased(int button) {
123    return DriverStation.getStickButtonReleased(m_port, button);
124  }
125
126  /**
127   * Constructs an event instance around this button's digital signal.
128   *
129   * @param button the button index
130   * @param loop the event loop instance to attach the event to.
131   * @return an event instance representing the button's digital signal attached to the given loop.
132   */
133  public BooleanEvent button(int button, EventLoop loop) {
134    return new BooleanEvent(loop, () -> getRawButton(button));
135  }
136
137  /**
138   * Get the value of the axis.
139   *
140   * @param axis The axis to read, starting at 0.
141   * @return The value of the axis.
142   */
143  public double getRawAxis(int axis) {
144    return DriverStation.getStickAxis(m_port, axis);
145  }
146
147  /**
148   * Get the angle in degrees of a POV on the HID.
149   *
150   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
151   * upper-left is 315).
152   *
153   * @param pov The index of the POV to read (starting at 0). Defaults to 0.
154   * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
155   */
156  public int getPOV(int pov) {
157    return DriverStation.getStickPOV(m_port, pov);
158  }
159
160  /**
161   * Get the angle in degrees of the default POV (index 0) on the HID.
162   *
163   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
164   * upper-left is 315).
165   *
166   * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
167   */
168  public int getPOV() {
169    return getPOV(0);
170  }
171
172  /**
173   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
174   *
175   * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90,
176   * upper-left is 315).
177   *
178   * @param angle POV angle in degrees, or -1 for the center / not pressed.
179   * @param loop the event loop instance to attach the event to.
180   * @return a BooleanEvent instance based around this angle of a POV on the HID.
181   */
182  public BooleanEvent pov(int angle, EventLoop loop) {
183    return pov(0, angle, loop);
184  }
185
186  /**
187   * Constructs a BooleanEvent instance based around this angle of a POV on the HID.
188   *
189   * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90,
190   * upper-left is 315).
191   *
192   * @param pov index of the POV to read (starting at 0). Defaults to 0.
193   * @param angle POV angle in degrees, or -1 for the center / not pressed.
194   * @param loop the event loop instance to attach the event to.
195   * @return a BooleanEvent instance based around this angle of a POV on the HID.
196   */
197  public BooleanEvent pov(int pov, int angle, EventLoop loop) {
198    return new BooleanEvent(loop, () -> getPOV(pov) == angle);
199  }
200
201  /**
202   * Constructs a BooleanEvent instance based around the 0 degree angle (up) of the default (index
203   * 0) POV on the HID.
204   *
205   * @param loop the event loop instance to attach the event to.
206   * @return a BooleanEvent instance based around the 0 degree angle of a POV on the HID.
207   */
208  public BooleanEvent povUp(EventLoop loop) {
209    return pov(0, loop);
210  }
211
212  /**
213   * Constructs a BooleanEvent instance based around the 45 degree angle (right up) of the default
214   * (index 0) POV on the HID.
215   *
216   * @param loop the event loop instance to attach the event to.
217   * @return a BooleanEvent instance based around the 45 degree angle of a POV on the HID.
218   */
219  public BooleanEvent povUpRight(EventLoop loop) {
220    return pov(45, loop);
221  }
222
223  /**
224   * Constructs a BooleanEvent instance based around the 90 degree angle (right) of the default
225   * (index 0) POV on the HID.
226   *
227   * @param loop the event loop instance to attach the event to.
228   * @return a BooleanEvent instance based around the 90 degree angle of a POV on the HID.
229   */
230  public BooleanEvent povRight(EventLoop loop) {
231    return pov(90, loop);
232  }
233
234  /**
235   * Constructs a BooleanEvent instance based around the 135 degree angle (right down) of the
236   * default (index 0) POV on the HID.
237   *
238   * @param loop the event loop instance to attach the event to.
239   * @return a BooleanEvent instance based around the 135 degree angle of a POV on the HID.
240   */
241  public BooleanEvent povDownRight(EventLoop loop) {
242    return pov(135, loop);
243  }
244
245  /**
246   * Constructs a BooleanEvent instance based around the 180 degree angle (down) of the default
247   * (index 0) POV on the HID.
248   *
249   * @param loop the event loop instance to attach the event to.
250   * @return a BooleanEvent instance based around the 180 degree angle of a POV on the HID.
251   */
252  public BooleanEvent povDown(EventLoop loop) {
253    return pov(180, loop);
254  }
255
256  /**
257   * Constructs a BooleanEvent instance based around the 225 degree angle (down left) of the default
258   * (index 0) POV on the HID.
259   *
260   * @param loop the event loop instance to attach the event to.
261   * @return a BooleanEvent instance based around the 225 degree angle of a POV on the HID.
262   */
263  public BooleanEvent povDownLeft(EventLoop loop) {
264    return pov(225, loop);
265  }
266
267  /**
268   * Constructs a BooleanEvent instance based around the 270 degree angle (left) of the default
269   * (index 0) POV on the HID.
270   *
271   * @param loop the event loop instance to attach the event to.
272   * @return a BooleanEvent instance based around the 270 degree angle of a POV on the HID.
273   */
274  public BooleanEvent povLeft(EventLoop loop) {
275    return pov(270, loop);
276  }
277
278  /**
279   * Constructs a BooleanEvent instance based around the 315 degree angle (left up) of the default
280   * (index 0) POV on the HID.
281   *
282   * @param loop the event loop instance to attach the event to.
283   * @return a BooleanEvent instance based around the 315 degree angle of a POV on the HID.
284   */
285  public BooleanEvent povUpLeft(EventLoop loop) {
286    return pov(315, loop);
287  }
288
289  /**
290   * Constructs a BooleanEvent instance based around the center (not pressed) of the default (index
291   * 0) POV on the HID.
292   *
293   * @param loop the event loop instance to attach the event to.
294   * @return a BooleanEvent instance based around the center of a POV on the HID.
295   */
296  public BooleanEvent povCenter(EventLoop loop) {
297    return pov(-1, loop);
298  }
299
300  /**
301   * Constructs an event instance that is true when the axis value is less than {@code threshold},
302   * attached to the given loop.
303   *
304   * @param axis The axis to read, starting at 0
305   * @param threshold The value below which this event should return true.
306   * @param loop the event loop instance to attach the event to.
307   * @return an event instance that is true when the axis value is less than the provided threshold.
308   */
309  public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) {
310    return new BooleanEvent(loop, () -> getRawAxis(axis) < threshold);
311  }
312
313  /**
314   * Constructs an event instance that is true when the axis value is greater than {@code
315   * threshold}, attached to the given loop.
316   *
317   * @param axis The axis to read, starting at 0
318   * @param threshold The value above which this event should return true.
319   * @param loop the event loop instance to attach the event to.
320   * @return an event instance that is true when the axis value is greater than the provided
321   *     threshold.
322   */
323  public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) {
324    return new BooleanEvent(loop, () -> getRawAxis(axis) > threshold);
325  }
326
327  /**
328   * Get the number of axes for the HID.
329   *
330   * @return the number of axis for the current HID
331   */
332  public int getAxisCount() {
333    return DriverStation.getStickAxisCount(m_port);
334  }
335
336  /**
337   * For the current HID, return the number of POVs.
338   *
339   * @return the number of POVs for the current HID
340   */
341  public int getPOVCount() {
342    return DriverStation.getStickPOVCount(m_port);
343  }
344
345  /**
346   * For the current HID, return the number of buttons.
347   *
348   * @return the number of buttons for the current HID
349   */
350  public int getButtonCount() {
351    return DriverStation.getStickButtonCount(m_port);
352  }
353
354  /**
355   * Get if the HID is connected.
356   *
357   * @return true if the HID is connected
358   */
359  public boolean isConnected() {
360    return DriverStation.isJoystickConnected(m_port);
361  }
362
363  /**
364   * Get the type of the HID.
365   *
366   * @return the type of the HID.
367   */
368  public HIDType getType() {
369    return HIDType.of(DriverStation.getJoystickType(m_port));
370  }
371
372  /**
373   * Get the name of the HID.
374   *
375   * @return the name of the HID.
376   */
377  public String getName() {
378    return DriverStation.getJoystickName(m_port);
379  }
380
381  /**
382   * Get the axis type of the provided joystick axis.
383   *
384   * @param axis The axis to read, starting at 0.
385   * @return the axis type of the given joystick axis
386   */
387  public int getAxisType(int axis) {
388    return DriverStation.getJoystickAxisType(m_port, axis);
389  }
390
391  /**
392   * Get the port number of the HID.
393   *
394   * @return The port number of the HID.
395   */
396  public int getPort() {
397    return m_port;
398  }
399
400  /**
401   * Set a single HID output value for the HID.
402   *
403   * @param outputNumber The index of the output to set (1-32)
404   * @param value The value to set the output to
405   */
406  public void setOutput(int outputNumber, boolean value) {
407    m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | ((value ? 1 : 0) << (outputNumber - 1));
408    DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
409  }
410
411  /**
412   * Set all HID output values for the HID.
413   *
414   * @param value The 32 bit output value (1 bit for each output)
415   */
416  public void setOutputs(int value) {
417    m_outputs = value;
418    DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
419  }
420
421  /**
422   * Set the rumble output for the HID. The DS currently supports 2 rumble values, left rumble and
423   * right rumble.
424   *
425   * @param type Which rumble value to set
426   * @param value The normalized value (0 to 1) to set the rumble to
427   */
428  public void setRumble(RumbleType type, double value) {
429    value = MathUtil.clamp(value, 0, 1);
430    short rumbleValue = (short) (value * 65535);
431
432    switch (type) {
433      case kLeftRumble:
434        this.m_leftRumble = rumbleValue;
435        break;
436      case kRightRumble:
437        this.m_rightRumble = rumbleValue;
438        break;
439      case kBothRumble:
440      default:
441        this.m_leftRumble = rumbleValue;
442        this.m_rightRumble = rumbleValue;
443        break;
444    }
445
446    DriverStationJNI.setJoystickOutputs(
447        (byte) this.m_port, this.m_outputs, this.m_leftRumble, this.m_rightRumble);
448  }
449}