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.math.Pair; 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 @SuppressWarnings("PMD.UseConcurrentHashMap") 074 private static final Map<Integer, HIDType> map = new HashMap<>(); 075 076 HIDType(int value) { 077 this.value = value; 078 } 079 080 static { 081 for (HIDType hidType : HIDType.values()) { 082 map.put(hidType.value, hidType); 083 } 084 } 085 086 /** 087 * Creates an HIDType with the given value. 088 * 089 * @param value HIDType's value. 090 * @return HIDType with the given value. 091 */ 092 public static HIDType of(int value) { 093 return map.get(value); 094 } 095 } 096 097 private final int m_port; 098 private int m_outputs; 099 private int m_leftRumble; 100 private int m_rightRumble; 101 private final Map<EventLoop, Map<Integer, BooleanEvent>> m_buttonCache = new HashMap<>(); 102 private final Map<EventLoop, Map<Pair<Integer, Double>, BooleanEvent>> m_axisLessThanCache = 103 new HashMap<>(); 104 private final Map<EventLoop, Map<Pair<Integer, Double>, BooleanEvent>> m_axisGreaterThanCache = 105 new HashMap<>(); 106 private final Map<EventLoop, Map<Integer, BooleanEvent>> m_povCache = new HashMap<>(); 107 108 /** 109 * Construct an instance of a device. 110 * 111 * @param port The port index on the Driver Station that the device is plugged into. 112 */ 113 public GenericHID(int port) { 114 m_port = port; 115 } 116 117 /** 118 * Get the button value (starting at button 1). 119 * 120 * <p>The buttons are returned in a single 16 bit value with one bit representing the state of 121 * each button. The appropriate button is returned as a boolean value. 122 * 123 * <p>This method returns true if the button is being held down at the time that this method is 124 * being called. 125 * 126 * @param button The button number to be read (starting at 1) 127 * @return The state of the button. 128 */ 129 public boolean getRawButton(int button) { 130 return DriverStation.getStickButton(m_port, (byte) button); 131 } 132 133 /** 134 * Whether the button was pressed since the last check. Button indexes begin at 1. 135 * 136 * <p>This method returns true if the button went from not pressed to held down since the last 137 * time this method was called. This is useful if you only want to call a function once when you 138 * press the button. 139 * 140 * @param button The button index, beginning at 1. 141 * @return Whether the button was pressed since the last check. 142 */ 143 public boolean getRawButtonPressed(int button) { 144 return DriverStation.getStickButtonPressed(m_port, (byte) button); 145 } 146 147 /** 148 * Whether the button was released since the last check. Button indexes begin at 1. 149 * 150 * <p>This method returns true if the button went from held down to not pressed since the last 151 * time this method was called. This is useful if you only want to call a function once when you 152 * release the button. 153 * 154 * @param button The button index, beginning at 1. 155 * @return Whether the button was released since the last check. 156 */ 157 public boolean getRawButtonReleased(int button) { 158 return DriverStation.getStickButtonReleased(m_port, button); 159 } 160 161 /** 162 * Constructs an event instance around this button's digital signal. 163 * 164 * @param button the button index 165 * @param loop the event loop instance to attach the event to. 166 * @return an event instance representing the button's digital signal attached to the given loop. 167 */ 168 public BooleanEvent button(int button, EventLoop loop) { 169 synchronized (m_buttonCache) { 170 var cache = m_buttonCache.computeIfAbsent(loop, k -> new HashMap<>()); 171 return cache.computeIfAbsent(button, k -> new BooleanEvent(loop, () -> getRawButton(k))); 172 } 173 } 174 175 /** 176 * Get the value of the axis. 177 * 178 * @param axis The axis to read, starting at 0. 179 * @return The value of the axis. 180 */ 181 public double getRawAxis(int axis) { 182 return DriverStation.getStickAxis(m_port, axis); 183 } 184 185 /** 186 * Get the angle in degrees of a POV on the HID. 187 * 188 * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, 189 * upper-left is 315). 190 * 191 * @param pov The index of the POV to read (starting at 0). Defaults to 0. 192 * @return the angle of the POV in degrees, or -1 if the POV is not pressed. 193 */ 194 public int getPOV(int pov) { 195 return DriverStation.getStickPOV(m_port, pov); 196 } 197 198 /** 199 * Get the angle in degrees of the default POV (index 0) on the HID. 200 * 201 * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, 202 * upper-left is 315). 203 * 204 * @return the angle of the POV in degrees, or -1 if the POV is not pressed. 205 */ 206 public int getPOV() { 207 return getPOV(0); 208 } 209 210 /** 211 * Constructs a BooleanEvent instance based around this angle of a POV on the HID. 212 * 213 * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90, 214 * upper-left is 315). 215 * 216 * @param angle POV angle in degrees, or -1 for the center / not pressed. 217 * @param loop the event loop instance to attach the event to. 218 * @return a BooleanEvent instance based around this angle of a POV on the HID. 219 */ 220 public BooleanEvent pov(int angle, EventLoop loop) { 221 return pov(0, angle, loop); 222 } 223 224 /** 225 * Constructs a BooleanEvent instance based around this angle of a POV on the HID. 226 * 227 * <p>The POV angles start at 0 in the up direction, and increase clockwise (e.g. right is 90, 228 * upper-left is 315). 229 * 230 * @param pov index of the POV to read (starting at 0). Defaults to 0. 231 * @param angle POV angle in degrees, or -1 for the center / not pressed. 232 * @param loop the event loop instance to attach the event to. 233 * @return a BooleanEvent instance based around this angle of a POV on the HID. 234 */ 235 public BooleanEvent pov(int pov, int angle, EventLoop loop) { 236 synchronized (m_povCache) { 237 var cache = m_povCache.computeIfAbsent(loop, k -> new HashMap<>()); 238 // angle can be -1, so use 3600 instead of 360 239 return cache.computeIfAbsent( 240 pov * 3600 + angle, k -> new BooleanEvent(loop, () -> getPOV(pov) == angle)); 241 } 242 } 243 244 /** 245 * Constructs a BooleanEvent instance based around the 0 degree angle (up) of the default (index 246 * 0) POV on the HID. 247 * 248 * @param loop the event loop instance to attach the event to. 249 * @return a BooleanEvent instance based around the 0 degree angle of a POV on the HID. 250 */ 251 public BooleanEvent povUp(EventLoop loop) { 252 return pov(0, loop); 253 } 254 255 /** 256 * Constructs a BooleanEvent instance based around the 45 degree angle (right up) of the default 257 * (index 0) POV on the HID. 258 * 259 * @param loop the event loop instance to attach the event to. 260 * @return a BooleanEvent instance based around the 45 degree angle of a POV on the HID. 261 */ 262 public BooleanEvent povUpRight(EventLoop loop) { 263 return pov(45, loop); 264 } 265 266 /** 267 * Constructs a BooleanEvent instance based around the 90 degree angle (right) of the default 268 * (index 0) POV on the HID. 269 * 270 * @param loop the event loop instance to attach the event to. 271 * @return a BooleanEvent instance based around the 90 degree angle of a POV on the HID. 272 */ 273 public BooleanEvent povRight(EventLoop loop) { 274 return pov(90, loop); 275 } 276 277 /** 278 * Constructs a BooleanEvent instance based around the 135 degree angle (right down) of the 279 * default (index 0) POV on the HID. 280 * 281 * @param loop the event loop instance to attach the event to. 282 * @return a BooleanEvent instance based around the 135 degree angle of a POV on the HID. 283 */ 284 public BooleanEvent povDownRight(EventLoop loop) { 285 return pov(135, loop); 286 } 287 288 /** 289 * Constructs a BooleanEvent instance based around the 180 degree angle (down) of the default 290 * (index 0) POV on the HID. 291 * 292 * @param loop the event loop instance to attach the event to. 293 * @return a BooleanEvent instance based around the 180 degree angle of a POV on the HID. 294 */ 295 public BooleanEvent povDown(EventLoop loop) { 296 return pov(180, loop); 297 } 298 299 /** 300 * Constructs a BooleanEvent instance based around the 225 degree angle (down left) of the default 301 * (index 0) POV on the HID. 302 * 303 * @param loop the event loop instance to attach the event to. 304 * @return a BooleanEvent instance based around the 225 degree angle of a POV on the HID. 305 */ 306 public BooleanEvent povDownLeft(EventLoop loop) { 307 return pov(225, loop); 308 } 309 310 /** 311 * Constructs a BooleanEvent instance based around the 270 degree angle (left) of the default 312 * (index 0) POV on the HID. 313 * 314 * @param loop the event loop instance to attach the event to. 315 * @return a BooleanEvent instance based around the 270 degree angle of a POV on the HID. 316 */ 317 public BooleanEvent povLeft(EventLoop loop) { 318 return pov(270, loop); 319 } 320 321 /** 322 * Constructs a BooleanEvent instance based around the 315 degree angle (left up) of the default 323 * (index 0) POV on the HID. 324 * 325 * @param loop the event loop instance to attach the event to. 326 * @return a BooleanEvent instance based around the 315 degree angle of a POV on the HID. 327 */ 328 public BooleanEvent povUpLeft(EventLoop loop) { 329 return pov(315, loop); 330 } 331 332 /** 333 * Constructs a BooleanEvent instance based around the center (not pressed) of the default (index 334 * 0) POV on the HID. 335 * 336 * @param loop the event loop instance to attach the event to. 337 * @return a BooleanEvent instance based around the center of a POV on the HID. 338 */ 339 public BooleanEvent povCenter(EventLoop loop) { 340 return pov(-1, loop); 341 } 342 343 /** 344 * Constructs an event instance that is true when the axis value is less than {@code threshold}, 345 * attached to the given loop. 346 * 347 * @param axis The axis to read, starting at 0 348 * @param threshold The value below which this event should return true. 349 * @param loop the event loop instance to attach the event to. 350 * @return an event instance that is true when the axis value is less than the provided threshold. 351 */ 352 public BooleanEvent axisLessThan(int axis, double threshold, EventLoop loop) { 353 synchronized (m_axisLessThanCache) { 354 var cache = m_axisLessThanCache.computeIfAbsent(loop, k -> new HashMap<>()); 355 return cache.computeIfAbsent( 356 Pair.of(axis, threshold), 357 k -> new BooleanEvent(loop, () -> getRawAxis(axis) < threshold)); 358 } 359 } 360 361 /** 362 * Constructs an event instance that is true when the axis value is greater than {@code 363 * threshold}, attached to the given loop. 364 * 365 * @param axis The axis to read, starting at 0 366 * @param threshold The value above which this event should return true. 367 * @param loop the event loop instance to attach the event to. 368 * @return an event instance that is true when the axis value is greater than the provided 369 * threshold. 370 */ 371 public BooleanEvent axisGreaterThan(int axis, double threshold, EventLoop loop) { 372 synchronized (m_axisGreaterThanCache) { 373 var cache = m_axisGreaterThanCache.computeIfAbsent(loop, k -> new HashMap<>()); 374 return cache.computeIfAbsent( 375 Pair.of(axis, threshold), 376 k -> new BooleanEvent(loop, () -> getRawAxis(axis) > threshold)); 377 } 378 } 379 380 /** 381 * Get the number of axes for the HID. 382 * 383 * @return the number of axis for the current HID 384 */ 385 public int getAxisCount() { 386 return DriverStation.getStickAxisCount(m_port); 387 } 388 389 /** 390 * For the current HID, return the number of POVs. 391 * 392 * @return the number of POVs for the current HID 393 */ 394 public int getPOVCount() { 395 return DriverStation.getStickPOVCount(m_port); 396 } 397 398 /** 399 * For the current HID, return the number of buttons. 400 * 401 * @return the number of buttons for the current HID 402 */ 403 public int getButtonCount() { 404 return DriverStation.getStickButtonCount(m_port); 405 } 406 407 /** 408 * Get if the HID is connected. 409 * 410 * @return true if the HID is connected 411 */ 412 public boolean isConnected() { 413 return DriverStation.isJoystickConnected(m_port); 414 } 415 416 /** 417 * Get the type of the HID. 418 * 419 * @return the type of the HID. 420 */ 421 public HIDType getType() { 422 return HIDType.of(DriverStation.getJoystickType(m_port)); 423 } 424 425 /** 426 * Get the name of the HID. 427 * 428 * @return the name of the HID. 429 */ 430 public String getName() { 431 return DriverStation.getJoystickName(m_port); 432 } 433 434 /** 435 * Get the axis type of the provided joystick axis. 436 * 437 * @param axis The axis to read, starting at 0. 438 * @return the axis type of the given joystick axis 439 */ 440 public int getAxisType(int axis) { 441 return DriverStation.getJoystickAxisType(m_port, axis); 442 } 443 444 /** 445 * Get the port number of the HID. 446 * 447 * @return The port number of the HID. 448 */ 449 public int getPort() { 450 return m_port; 451 } 452 453 /** 454 * Set a single HID output value for the HID. 455 * 456 * @param outputNumber The index of the output to set (1-32) 457 * @param value The value to set the output to 458 */ 459 public void setOutput(int outputNumber, boolean value) { 460 m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | ((value ? 1 : 0) << (outputNumber - 1)); 461 DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble); 462 } 463 464 /** 465 * Set all HID output values for the HID. 466 * 467 * @param value The 32 bit output value (1 bit for each output) 468 */ 469 public void setOutputs(int value) { 470 m_outputs = value; 471 DriverStationJNI.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble); 472 } 473 474 /** 475 * Set the rumble output for the HID. The DS currently supports 2 rumble values, left rumble and 476 * right rumble. 477 * 478 * @param type Which rumble value to set 479 * @param value The normalized value (0 to 1) to set the rumble to 480 */ 481 public void setRumble(RumbleType type, double value) { 482 value = MathUtil.clamp(value, 0, 1); 483 int rumbleValue = (int) (value * 65535); 484 switch (type) { 485 case kLeftRumble -> this.m_leftRumble = rumbleValue; 486 case kRightRumble -> this.m_rightRumble = rumbleValue; 487 default -> { 488 this.m_leftRumble = rumbleValue; 489 this.m_rightRumble = rumbleValue; 490 } 491 } 492 493 DriverStationJNI.setJoystickOutputs( 494 (byte) this.m_port, this.m_outputs, this.m_leftRumble, this.m_rightRumble); 495 } 496}