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