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