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