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.AllianceStationID; 008import edu.wpi.first.hal.ControlWord; 009import edu.wpi.first.hal.DriverStationJNI; 010import edu.wpi.first.hal.HAL; 011import edu.wpi.first.hal.MatchInfoData; 012import edu.wpi.first.networktables.BooleanPublisher; 013import edu.wpi.first.networktables.IntegerPublisher; 014import edu.wpi.first.networktables.NetworkTableInstance; 015import edu.wpi.first.networktables.StringPublisher; 016import edu.wpi.first.networktables.StringTopic; 017import edu.wpi.first.util.EventVector; 018import edu.wpi.first.util.WPIUtilJNI; 019import edu.wpi.first.util.datalog.BooleanArrayLogEntry; 020import edu.wpi.first.util.datalog.BooleanLogEntry; 021import edu.wpi.first.util.datalog.DataLog; 022import edu.wpi.first.util.datalog.FloatArrayLogEntry; 023import edu.wpi.first.util.datalog.IntegerArrayLogEntry; 024import java.nio.ByteBuffer; 025import java.util.Map; 026import java.util.Optional; 027import java.util.OptionalInt; 028import java.util.concurrent.locks.ReentrantLock; 029 030/** Provide access to the network communication data to / from the Driver Station. */ 031public final class DriverStation { 032 /** Number of Joystick ports. */ 033 public static final int kJoystickPorts = 6; 034 035 private static final class HALJoystickButtons { 036 public int m_buttons; 037 public byte m_count; 038 } 039 040 private static class HALJoystickAxes { 041 public final float[] m_axes; 042 public int m_count; 043 044 HALJoystickAxes(int count) { 045 m_axes = new float[count]; 046 } 047 } 048 049 private static class HALJoystickAxesRaw { 050 public final int[] m_axes; 051 052 @SuppressWarnings("unused") 053 public int m_count; 054 055 HALJoystickAxesRaw(int count) { 056 m_axes = new int[count]; 057 } 058 } 059 060 private static class HALJoystickPOVs { 061 public final short[] m_povs; 062 public int m_count; 063 064 HALJoystickPOVs(int count) { 065 m_povs = new short[count]; 066 for (int i = 0; i < count; i++) { 067 m_povs[i] = -1; 068 } 069 } 070 } 071 072 /** The robot alliance that the robot is a part of. */ 073 public enum Alliance { 074 /** Red alliance. */ 075 Red, 076 /** Blue alliance. */ 077 Blue 078 } 079 080 /** The type of robot match that the robot is part of. */ 081 public enum MatchType { 082 /** None. */ 083 None, 084 /** Practice. */ 085 Practice, 086 /** Qualification. */ 087 Qualification, 088 /** Elimination. */ 089 Elimination 090 } 091 092 private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0; 093 private static double m_nextMessageTime; 094 095 @SuppressWarnings("MemberName") 096 private static class MatchDataSender { 097 private static final String kSmartDashboardType = "FMSInfo"; 098 099 final StringPublisher gameSpecificMessage; 100 final StringPublisher eventName; 101 final IntegerPublisher matchNumber; 102 final IntegerPublisher replayNumber; 103 final IntegerPublisher matchType; 104 final BooleanPublisher alliance; 105 final IntegerPublisher station; 106 final IntegerPublisher controlWord; 107 boolean oldIsRedAlliance = true; 108 int oldStationNumber = 1; 109 String oldEventName = ""; 110 String oldGameSpecificMessage = ""; 111 int oldMatchNumber; 112 int oldReplayNumber; 113 int oldMatchType; 114 int oldControlWord; 115 116 MatchDataSender() { 117 var table = NetworkTableInstance.getDefault().getTable("FMSInfo"); 118 table 119 .getStringTopic(".type") 120 .publishEx( 121 StringTopic.kTypeString, "{\"SmartDashboard\":\"" + kSmartDashboardType + "\"}") 122 .set(kSmartDashboardType); 123 gameSpecificMessage = table.getStringTopic("GameSpecificMessage").publish(); 124 gameSpecificMessage.set(""); 125 eventName = table.getStringTopic("EventName").publish(); 126 eventName.set(""); 127 matchNumber = table.getIntegerTopic("MatchNumber").publish(); 128 matchNumber.set(0); 129 replayNumber = table.getIntegerTopic("ReplayNumber").publish(); 130 replayNumber.set(0); 131 matchType = table.getIntegerTopic("MatchType").publish(); 132 matchType.set(0); 133 alliance = table.getBooleanTopic("IsRedAlliance").publish(); 134 alliance.set(true); 135 station = table.getIntegerTopic("StationNumber").publish(); 136 station.set(1); 137 controlWord = table.getIntegerTopic("FMSControlData").publish(); 138 controlWord.set(0); 139 } 140 141 private void sendMatchData() { 142 AllianceStationID allianceID = DriverStationJNI.getAllianceStation(); 143 final int stationNumber = 144 switch (allianceID) { 145 case Blue1, Red1 -> 1; 146 case Blue2, Red2 -> 2; 147 case Blue3, Red3, Unknown -> 3; 148 }; 149 final boolean isRedAlliance = 150 switch (allianceID) { 151 case Blue1, Blue2, Blue3 -> false; 152 case Red1, Red2, Red3, Unknown -> true; 153 }; 154 155 String currentEventName; 156 String currentGameSpecificMessage; 157 int currentMatchNumber; 158 int currentReplayNumber; 159 int currentMatchType; 160 int currentControlWord; 161 m_cacheDataMutex.lock(); 162 try { 163 currentEventName = DriverStation.m_matchInfo.eventName; 164 currentGameSpecificMessage = DriverStation.m_matchInfo.gameSpecificMessage; 165 currentMatchNumber = DriverStation.m_matchInfo.matchNumber; 166 currentReplayNumber = DriverStation.m_matchInfo.replayNumber; 167 currentMatchType = DriverStation.m_matchInfo.matchType; 168 } finally { 169 m_cacheDataMutex.unlock(); 170 } 171 currentControlWord = DriverStationJNI.nativeGetControlWord(); 172 173 if (oldIsRedAlliance != isRedAlliance) { 174 alliance.set(isRedAlliance); 175 oldIsRedAlliance = isRedAlliance; 176 } 177 if (oldStationNumber != stationNumber) { 178 station.set(stationNumber); 179 oldStationNumber = stationNumber; 180 } 181 if (!oldEventName.equals(currentEventName)) { 182 eventName.set(currentEventName); 183 oldEventName = currentEventName; 184 } 185 if (!oldGameSpecificMessage.equals(currentGameSpecificMessage)) { 186 gameSpecificMessage.set(currentGameSpecificMessage); 187 oldGameSpecificMessage = currentGameSpecificMessage; 188 } 189 if (currentMatchNumber != oldMatchNumber) { 190 matchNumber.set(currentMatchNumber); 191 oldMatchNumber = currentMatchNumber; 192 } 193 if (currentReplayNumber != oldReplayNumber) { 194 replayNumber.set(currentReplayNumber); 195 oldReplayNumber = currentReplayNumber; 196 } 197 if (currentMatchType != oldMatchType) { 198 matchType.set(currentMatchType); 199 oldMatchType = currentMatchType; 200 } 201 if (currentControlWord != oldControlWord) { 202 controlWord.set(currentControlWord); 203 oldControlWord = currentControlWord; 204 } 205 } 206 } 207 208 private static class JoystickLogSender { 209 JoystickLogSender(DataLog log, int stick, long timestamp) { 210 m_stick = stick; 211 212 m_logButtons = new BooleanArrayLogEntry(log, "DS:joystick" + stick + "/buttons", timestamp); 213 m_logAxes = new FloatArrayLogEntry(log, "DS:joystick" + stick + "/axes", timestamp); 214 m_logPOVs = new IntegerArrayLogEntry(log, "DS:joystick" + stick + "/povs", timestamp); 215 216 appendButtons(m_joystickButtons[m_stick], timestamp); 217 appendAxes(m_joystickAxes[m_stick], timestamp); 218 appendPOVs(m_joystickPOVs[m_stick], timestamp); 219 } 220 221 public void send(long timestamp) { 222 HALJoystickButtons buttons = m_joystickButtons[m_stick]; 223 if (buttons.m_count != m_prevButtons.m_count 224 || buttons.m_buttons != m_prevButtons.m_buttons) { 225 appendButtons(buttons, timestamp); 226 } 227 228 HALJoystickAxes axes = m_joystickAxes[m_stick]; 229 int count = axes.m_count; 230 boolean needToLog = false; 231 if (count != m_prevAxes.m_count) { 232 needToLog = true; 233 } else { 234 for (int i = 0; i < count; i++) { 235 if (axes.m_axes[i] != m_prevAxes.m_axes[i]) { 236 needToLog = true; 237 break; 238 } 239 } 240 } 241 if (needToLog) { 242 appendAxes(axes, timestamp); 243 } 244 245 HALJoystickPOVs povs = m_joystickPOVs[m_stick]; 246 count = m_joystickPOVs[m_stick].m_count; 247 needToLog = false; 248 if (count != m_prevPOVs.m_count) { 249 needToLog = true; 250 } else { 251 for (int i = 0; i < count; i++) { 252 if (povs.m_povs[i] != m_prevPOVs.m_povs[i]) { 253 needToLog = true; 254 break; 255 } 256 } 257 } 258 if (needToLog) { 259 appendPOVs(povs, timestamp); 260 } 261 } 262 263 void appendButtons(HALJoystickButtons buttons, long timestamp) { 264 byte count = buttons.m_count; 265 if (m_sizedButtons == null || m_sizedButtons.length != count) { 266 m_sizedButtons = new boolean[count]; 267 } 268 int buttonsValue = buttons.m_buttons; 269 for (int i = 0; i < count; i++) { 270 m_sizedButtons[i] = (buttonsValue & (1 << i)) != 0; 271 } 272 m_logButtons.append(m_sizedButtons, timestamp); 273 m_prevButtons.m_count = count; 274 m_prevButtons.m_buttons = buttons.m_buttons; 275 } 276 277 void appendAxes(HALJoystickAxes axes, long timestamp) { 278 int count = axes.m_count; 279 if (m_sizedAxes == null || m_sizedAxes.length != count) { 280 m_sizedAxes = new float[count]; 281 } 282 System.arraycopy(axes.m_axes, 0, m_sizedAxes, 0, count); 283 m_logAxes.append(m_sizedAxes, timestamp); 284 m_prevAxes.m_count = count; 285 System.arraycopy(axes.m_axes, 0, m_prevAxes.m_axes, 0, count); 286 } 287 288 @SuppressWarnings("PMD.AvoidArrayLoops") 289 void appendPOVs(HALJoystickPOVs povs, long timestamp) { 290 int count = povs.m_count; 291 if (m_sizedPOVs == null || m_sizedPOVs.length != count) { 292 m_sizedPOVs = new long[count]; 293 } 294 for (int i = 0; i < count; i++) { 295 m_sizedPOVs[i] = povs.m_povs[i]; 296 } 297 m_logPOVs.append(m_sizedPOVs, timestamp); 298 m_prevPOVs.m_count = count; 299 System.arraycopy(povs.m_povs, 0, m_prevPOVs.m_povs, 0, count); 300 } 301 302 final int m_stick; 303 boolean[] m_sizedButtons; 304 float[] m_sizedAxes; 305 long[] m_sizedPOVs; 306 final HALJoystickButtons m_prevButtons = new HALJoystickButtons(); 307 final HALJoystickAxes m_prevAxes = new HALJoystickAxes(DriverStationJNI.kMaxJoystickAxes); 308 final HALJoystickPOVs m_prevPOVs = new HALJoystickPOVs(DriverStationJNI.kMaxJoystickPOVs); 309 final BooleanArrayLogEntry m_logButtons; 310 final FloatArrayLogEntry m_logAxes; 311 final IntegerArrayLogEntry m_logPOVs; 312 } 313 314 private static class DataLogSender { 315 DataLogSender(DataLog log, boolean logJoysticks, long timestamp) { 316 m_logEnabled = new BooleanLogEntry(log, "DS:enabled", timestamp); 317 m_logAutonomous = new BooleanLogEntry(log, "DS:autonomous", timestamp); 318 m_logTest = new BooleanLogEntry(log, "DS:test", timestamp); 319 m_logEstop = new BooleanLogEntry(log, "DS:estop", timestamp); 320 321 // append initial control word values 322 m_wasEnabled = m_controlWordCache.getEnabled(); 323 m_wasAutonomous = m_controlWordCache.getAutonomous(); 324 m_wasTest = m_controlWordCache.getTest(); 325 m_wasEstop = m_controlWordCache.getEStop(); 326 327 m_logEnabled.append(m_wasEnabled, timestamp); 328 m_logAutonomous.append(m_wasAutonomous, timestamp); 329 m_logTest.append(m_wasTest, timestamp); 330 m_logEstop.append(m_wasEstop, timestamp); 331 332 if (logJoysticks) { 333 m_joysticks = new JoystickLogSender[kJoystickPorts]; 334 for (int i = 0; i < kJoystickPorts; i++) { 335 m_joysticks[i] = new JoystickLogSender(log, i, timestamp); 336 } 337 } else { 338 m_joysticks = new JoystickLogSender[0]; 339 } 340 } 341 342 public void send(long timestamp) { 343 // append control word value changes 344 boolean enabled = m_controlWordCache.getEnabled(); 345 if (enabled != m_wasEnabled) { 346 m_logEnabled.append(enabled, timestamp); 347 } 348 m_wasEnabled = enabled; 349 350 boolean autonomous = m_controlWordCache.getAutonomous(); 351 if (autonomous != m_wasAutonomous) { 352 m_logAutonomous.append(autonomous, timestamp); 353 } 354 m_wasAutonomous = autonomous; 355 356 boolean test = m_controlWordCache.getTest(); 357 if (test != m_wasTest) { 358 m_logTest.append(test, timestamp); 359 } 360 m_wasTest = test; 361 362 boolean estop = m_controlWordCache.getEStop(); 363 if (estop != m_wasEstop) { 364 m_logEstop.append(estop, timestamp); 365 } 366 m_wasEstop = estop; 367 368 // append joystick value changes 369 for (JoystickLogSender joystick : m_joysticks) { 370 joystick.send(timestamp); 371 } 372 } 373 374 boolean m_wasEnabled; 375 boolean m_wasAutonomous; 376 boolean m_wasTest; 377 boolean m_wasEstop; 378 final BooleanLogEntry m_logEnabled; 379 final BooleanLogEntry m_logAutonomous; 380 final BooleanLogEntry m_logTest; 381 final BooleanLogEntry m_logEstop; 382 383 final JoystickLogSender[] m_joysticks; 384 } 385 386 // Joystick User Data 387 private static HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts]; 388 private static HALJoystickAxesRaw[] m_joystickAxesRaw = new HALJoystickAxesRaw[kJoystickPorts]; 389 private static HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts]; 390 private static HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts]; 391 private static MatchInfoData m_matchInfo = new MatchInfoData(); 392 private static ControlWord m_controlWord = new ControlWord(); 393 private static EventVector m_refreshEvents = new EventVector(); 394 395 // Joystick Cached Data 396 private static HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts]; 397 private static HALJoystickAxesRaw[] m_joystickAxesRawCache = 398 new HALJoystickAxesRaw[kJoystickPorts]; 399 private static HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts]; 400 private static HALJoystickButtons[] m_joystickButtonsCache = 401 new HALJoystickButtons[kJoystickPorts]; 402 private static MatchInfoData m_matchInfoCache = new MatchInfoData(); 403 private static ControlWord m_controlWordCache = new ControlWord(); 404 405 // Joystick button rising/falling edge flags 406 private static int[] m_joystickButtonsPressed = new int[kJoystickPorts]; 407 private static int[] m_joystickButtonsReleased = new int[kJoystickPorts]; 408 409 // preallocated byte buffer for button count 410 private static final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1); 411 412 private static final MatchDataSender m_matchDataSender; 413 private static DataLogSender m_dataLogSender; 414 415 private static final ReentrantLock m_cacheDataMutex = new ReentrantLock(); 416 417 private static boolean m_silenceJoystickWarning; 418 419 /** 420 * DriverStation constructor. 421 * 422 * <p>The single DriverStation instance is created statically with the instance static member 423 * variable. 424 */ 425 private DriverStation() {} 426 427 static { 428 HAL.initialize(500, 0); 429 430 for (int i = 0; i < kJoystickPorts; i++) { 431 m_joystickButtons[i] = new HALJoystickButtons(); 432 m_joystickAxes[i] = new HALJoystickAxes(DriverStationJNI.kMaxJoystickAxes); 433 m_joystickAxesRaw[i] = new HALJoystickAxesRaw(DriverStationJNI.kMaxJoystickAxes); 434 m_joystickPOVs[i] = new HALJoystickPOVs(DriverStationJNI.kMaxJoystickPOVs); 435 436 m_joystickButtonsCache[i] = new HALJoystickButtons(); 437 m_joystickAxesCache[i] = new HALJoystickAxes(DriverStationJNI.kMaxJoystickAxes); 438 m_joystickAxesRawCache[i] = new HALJoystickAxesRaw(DriverStationJNI.kMaxJoystickAxes); 439 m_joystickPOVsCache[i] = new HALJoystickPOVs(DriverStationJNI.kMaxJoystickPOVs); 440 } 441 442 m_matchDataSender = new MatchDataSender(); 443 } 444 445 /** 446 * Report error to Driver Station. Optionally appends Stack trace to error message. 447 * 448 * @param error The error to report. 449 * @param printTrace If true, append stack trace to error string 450 */ 451 public static void reportError(String error, boolean printTrace) { 452 reportErrorImpl(true, 1, error, printTrace); 453 } 454 455 /** 456 * Report error to Driver Station. Appends provided stack trace to error message. 457 * 458 * @param error The error to report. 459 * @param stackTrace The stack trace to append 460 */ 461 public static void reportError(String error, StackTraceElement[] stackTrace) { 462 reportErrorImpl(true, 1, error, stackTrace); 463 } 464 465 /** 466 * Report warning to Driver Station. Optionally appends Stack trace to warning message. 467 * 468 * @param warning The warning to report. 469 * @param printTrace If true, append stack trace to warning string 470 */ 471 public static void reportWarning(String warning, boolean printTrace) { 472 reportErrorImpl(false, 1, warning, printTrace); 473 } 474 475 /** 476 * Report warning to Driver Station. Appends provided stack trace to warning message. 477 * 478 * @param warning The warning to report. 479 * @param stackTrace The stack trace to append 480 */ 481 public static void reportWarning(String warning, StackTraceElement[] stackTrace) { 482 reportErrorImpl(false, 1, warning, stackTrace); 483 } 484 485 private static void reportErrorImpl(boolean isError, int code, String error, boolean printTrace) { 486 reportErrorImpl(isError, code, error, printTrace, Thread.currentThread().getStackTrace(), 3); 487 } 488 489 private static void reportErrorImpl( 490 boolean isError, int code, String error, StackTraceElement[] stackTrace) { 491 reportErrorImpl(isError, code, error, true, stackTrace, 0); 492 } 493 494 private static void reportErrorImpl( 495 boolean isError, 496 int code, 497 String error, 498 boolean printTrace, 499 StackTraceElement[] stackTrace, 500 int stackTraceFirst) { 501 String locString; 502 if (stackTrace.length >= stackTraceFirst + 1) { 503 locString = stackTrace[stackTraceFirst].toString(); 504 } else { 505 locString = ""; 506 } 507 StringBuilder traceString = new StringBuilder(); 508 if (printTrace) { 509 boolean haveLoc = false; 510 for (int i = stackTraceFirst; i < stackTrace.length; i++) { 511 String loc = stackTrace[i].toString(); 512 traceString.append("\tat ").append(loc).append('\n'); 513 // get first user function 514 if (!haveLoc && !loc.startsWith("edu.wpi.first")) { 515 locString = loc; 516 haveLoc = true; 517 } 518 } 519 } 520 DriverStationJNI.sendError( 521 isError, code, false, error, locString, traceString.toString(), true); 522 } 523 524 /** 525 * The state of one joystick button. Button indexes begin at 1. 526 * 527 * @param stick The joystick to read. 528 * @param button The button index, beginning at 1. 529 * @return The state of the joystick button. 530 */ 531 public static boolean getStickButton(final int stick, final int button) { 532 if (stick < 0 || stick >= kJoystickPorts) { 533 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 534 } 535 if (button <= 0) { 536 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 537 return false; 538 } 539 540 m_cacheDataMutex.lock(); 541 try { 542 if (button <= m_joystickButtons[stick].m_count) { 543 return (m_joystickButtons[stick].m_buttons & 1 << (button - 1)) != 0; 544 } 545 } finally { 546 m_cacheDataMutex.unlock(); 547 } 548 549 reportJoystickUnpluggedWarning( 550 "Joystick Button " 551 + button 552 + " on port " 553 + stick 554 + " not available, check if controller is plugged in"); 555 return false; 556 } 557 558 /** 559 * Whether one joystick button was pressed since the last check. Button indexes begin at 1. 560 * 561 * @param stick The joystick to read. 562 * @param button The button index, beginning at 1. 563 * @return Whether the joystick button was pressed since the last check. 564 */ 565 public static boolean getStickButtonPressed(final int stick, final int button) { 566 if (button <= 0) { 567 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 568 return false; 569 } 570 if (stick < 0 || stick >= kJoystickPorts) { 571 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 572 } 573 574 m_cacheDataMutex.lock(); 575 try { 576 if (button <= m_joystickButtons[stick].m_count) { 577 // If button was pressed, clear flag and return true 578 if ((m_joystickButtonsPressed[stick] & 1 << (button - 1)) != 0) { 579 m_joystickButtonsPressed[stick] &= ~(1 << (button - 1)); 580 return true; 581 } else { 582 return false; 583 } 584 } 585 } finally { 586 m_cacheDataMutex.unlock(); 587 } 588 589 reportJoystickUnpluggedWarning( 590 "Joystick Button " 591 + button 592 + " on port " 593 + stick 594 + " not available, check if controller is plugged in"); 595 return false; 596 } 597 598 /** 599 * Whether one joystick button was released since the last check. Button indexes begin at 1. 600 * 601 * @param stick The joystick to read. 602 * @param button The button index, beginning at 1. 603 * @return Whether the joystick button was released since the last check. 604 */ 605 public static boolean getStickButtonReleased(final int stick, final int button) { 606 if (button <= 0) { 607 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 608 return false; 609 } 610 if (stick < 0 || stick >= kJoystickPorts) { 611 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 612 } 613 614 m_cacheDataMutex.lock(); 615 try { 616 if (button <= m_joystickButtons[stick].m_count) { 617 // If button was released, clear flag and return true 618 if ((m_joystickButtonsReleased[stick] & 1 << (button - 1)) != 0) { 619 m_joystickButtonsReleased[stick] &= ~(1 << (button - 1)); 620 return true; 621 } else { 622 return false; 623 } 624 } 625 } finally { 626 m_cacheDataMutex.unlock(); 627 } 628 629 reportJoystickUnpluggedWarning( 630 "Joystick Button " 631 + button 632 + " on port " 633 + stick 634 + " not available, check if controller is plugged in"); 635 return false; 636 } 637 638 /** 639 * Get the value of the axis on a joystick. This depends on the mapping of the joystick connected 640 * to the specified port. 641 * 642 * @param stick The joystick to read. 643 * @param axis The analog axis value to read from the joystick. 644 * @return The value of the axis on the joystick. 645 */ 646 public static double getStickAxis(int stick, int axis) { 647 if (stick < 0 || stick >= kJoystickPorts) { 648 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 649 } 650 if (axis < 0 || axis >= DriverStationJNI.kMaxJoystickAxes) { 651 throw new IllegalArgumentException("Joystick axis is out of range"); 652 } 653 654 m_cacheDataMutex.lock(); 655 try { 656 if (axis < m_joystickAxes[stick].m_count) { 657 return m_joystickAxes[stick].m_axes[axis]; 658 } 659 } finally { 660 m_cacheDataMutex.unlock(); 661 } 662 663 reportJoystickUnpluggedWarning( 664 "Joystick axis " 665 + axis 666 + " on port " 667 + stick 668 + " not available, check if controller is plugged in"); 669 return 0.0; 670 } 671 672 /** 673 * Get the state of a POV on the joystick. 674 * 675 * @param stick The joystick to read. 676 * @param pov The POV to read. 677 * @return the angle of the POV in degrees, or -1 if the POV is not pressed. 678 */ 679 public static int getStickPOV(int stick, int pov) { 680 if (stick < 0 || stick >= kJoystickPorts) { 681 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 682 } 683 if (pov < 0 || pov >= DriverStationJNI.kMaxJoystickPOVs) { 684 throw new IllegalArgumentException("Joystick POV is out of range"); 685 } 686 687 m_cacheDataMutex.lock(); 688 try { 689 if (pov < m_joystickPOVs[stick].m_count) { 690 return m_joystickPOVs[stick].m_povs[pov]; 691 } 692 } finally { 693 m_cacheDataMutex.unlock(); 694 } 695 696 reportJoystickUnpluggedWarning( 697 "Joystick POV " 698 + pov 699 + " on port " 700 + stick 701 + " not available, check if controller is plugged in"); 702 return -1; 703 } 704 705 /** 706 * The state of the buttons on the joystick. 707 * 708 * @param stick The joystick to read. 709 * @return The state of the buttons on the joystick. 710 */ 711 public static int getStickButtons(final int stick) { 712 if (stick < 0 || stick >= kJoystickPorts) { 713 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 714 } 715 716 m_cacheDataMutex.lock(); 717 try { 718 return m_joystickButtons[stick].m_buttons; 719 } finally { 720 m_cacheDataMutex.unlock(); 721 } 722 } 723 724 /** 725 * Returns the number of axes on a given joystick port. 726 * 727 * @param stick The joystick port number 728 * @return The number of axes on the indicated joystick 729 */ 730 public static int getStickAxisCount(int stick) { 731 if (stick < 0 || stick >= kJoystickPorts) { 732 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 733 } 734 735 m_cacheDataMutex.lock(); 736 try { 737 return m_joystickAxes[stick].m_count; 738 } finally { 739 m_cacheDataMutex.unlock(); 740 } 741 } 742 743 /** 744 * Returns the number of povs on a given joystick port. 745 * 746 * @param stick The joystick port number 747 * @return The number of povs on the indicated joystick 748 */ 749 public static int getStickPOVCount(int stick) { 750 if (stick < 0 || stick >= kJoystickPorts) { 751 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 752 } 753 754 m_cacheDataMutex.lock(); 755 try { 756 return m_joystickPOVs[stick].m_count; 757 } finally { 758 m_cacheDataMutex.unlock(); 759 } 760 } 761 762 /** 763 * Gets the number of buttons on a joystick. 764 * 765 * @param stick The joystick port number 766 * @return The number of buttons on the indicated joystick 767 */ 768 public static int getStickButtonCount(int stick) { 769 if (stick < 0 || stick >= kJoystickPorts) { 770 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 771 } 772 773 m_cacheDataMutex.lock(); 774 try { 775 return m_joystickButtons[stick].m_count; 776 } finally { 777 m_cacheDataMutex.unlock(); 778 } 779 } 780 781 /** 782 * Gets the value of isXbox on a joystick. 783 * 784 * @param stick The joystick port number 785 * @return A boolean that returns the value of isXbox 786 */ 787 public static boolean getJoystickIsXbox(int stick) { 788 if (stick < 0 || stick >= kJoystickPorts) { 789 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 790 } 791 792 return DriverStationJNI.getJoystickIsXbox((byte) stick) == 1; 793 } 794 795 /** 796 * Gets the value of type on a joystick. 797 * 798 * @param stick The joystick port number 799 * @return The value of type 800 */ 801 public static int getJoystickType(int stick) { 802 if (stick < 0 || stick >= kJoystickPorts) { 803 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 804 } 805 806 return DriverStationJNI.getJoystickType((byte) stick); 807 } 808 809 /** 810 * Gets the name of the joystick at a port. 811 * 812 * @param stick The joystick port number 813 * @return The value of name 814 */ 815 public static String getJoystickName(int stick) { 816 if (stick < 0 || stick >= kJoystickPorts) { 817 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 818 } 819 820 return DriverStationJNI.getJoystickName((byte) stick); 821 } 822 823 /** 824 * Returns the types of Axes on a given joystick port. 825 * 826 * @param stick The joystick port number 827 * @param axis The target axis 828 * @return What type of axis the axis is reporting to be 829 */ 830 public static int getJoystickAxisType(int stick, int axis) { 831 if (stick < 0 || stick >= kJoystickPorts) { 832 throw new IllegalArgumentException("Joystick index is out of range, should be 0-5"); 833 } 834 835 return DriverStationJNI.getJoystickAxisType((byte) stick, (byte) axis); 836 } 837 838 /** 839 * Returns if a joystick is connected to the Driver Station. 840 * 841 * <p>This makes a best effort guess by looking at the reported number of axis, buttons, and POVs 842 * attached. 843 * 844 * @param stick The joystick port number 845 * @return true if a joystick is connected 846 */ 847 public static boolean isJoystickConnected(int stick) { 848 return getStickAxisCount(stick) > 0 849 || getStickButtonCount(stick) > 0 850 || getStickPOVCount(stick) > 0; 851 } 852 853 /** 854 * Gets a value indicating whether the Driver Station requires the robot to be enabled. 855 * 856 * @return True if the robot is enabled, false otherwise. 857 */ 858 public static boolean isEnabled() { 859 m_cacheDataMutex.lock(); 860 try { 861 return m_controlWord.getEnabled() && m_controlWord.getDSAttached(); 862 } finally { 863 m_cacheDataMutex.unlock(); 864 } 865 } 866 867 /** 868 * Gets a value indicating whether the Driver Station requires the robot to be disabled. 869 * 870 * @return True if the robot should be disabled, false otherwise. 871 */ 872 public static boolean isDisabled() { 873 return !isEnabled(); 874 } 875 876 /** 877 * Gets a value indicating whether the Robot is e-stopped. 878 * 879 * @return True if the robot is e-stopped, false otherwise. 880 */ 881 public static boolean isEStopped() { 882 m_cacheDataMutex.lock(); 883 try { 884 return m_controlWord.getEStop(); 885 } finally { 886 m_cacheDataMutex.unlock(); 887 } 888 } 889 890 /** 891 * Gets a value indicating whether the Driver Station requires the robot to be running in 892 * autonomous mode. 893 * 894 * @return True if autonomous mode should be enabled, false otherwise. 895 */ 896 public static boolean isAutonomous() { 897 m_cacheDataMutex.lock(); 898 try { 899 return m_controlWord.getAutonomous(); 900 } finally { 901 m_cacheDataMutex.unlock(); 902 } 903 } 904 905 /** 906 * Gets a value indicating whether the Driver Station requires the robot to be running in 907 * autonomous mode and enabled. 908 * 909 * @return True if autonomous should be set and the robot should be enabled. 910 */ 911 public static boolean isAutonomousEnabled() { 912 m_cacheDataMutex.lock(); 913 try { 914 return m_controlWord.getAutonomous() && m_controlWord.getEnabled(); 915 } finally { 916 m_cacheDataMutex.unlock(); 917 } 918 } 919 920 /** 921 * Gets a value indicating whether the Driver Station requires the robot to be running in 922 * operator-controlled mode. 923 * 924 * @return True if operator-controlled mode should be enabled, false otherwise. 925 */ 926 public static boolean isTeleop() { 927 return !(isAutonomous() || isTest()); 928 } 929 930 /** 931 * Gets a value indicating whether the Driver Station requires the robot to be running in 932 * operator-controller mode and enabled. 933 * 934 * @return True if operator-controlled mode should be set and the robot should be enabled. 935 */ 936 public static boolean isTeleopEnabled() { 937 m_cacheDataMutex.lock(); 938 try { 939 return !m_controlWord.getAutonomous() 940 && !m_controlWord.getTest() 941 && m_controlWord.getEnabled(); 942 } finally { 943 m_cacheDataMutex.unlock(); 944 } 945 } 946 947 /** 948 * Gets a value indicating whether the Driver Station requires the robot to be running in Test 949 * mode. 950 * 951 * @return True if test mode should be enabled, false otherwise. 952 */ 953 public static boolean isTest() { 954 m_cacheDataMutex.lock(); 955 try { 956 return m_controlWord.getTest(); 957 } finally { 958 m_cacheDataMutex.unlock(); 959 } 960 } 961 962 /** 963 * Gets a value indicating whether the Driver Station requires the robot to be running in Test 964 * mode and enabled. 965 * 966 * @return True if test mode should be set and the robot should be enabled. 967 */ 968 public static boolean isTestEnabled() { 969 m_cacheDataMutex.lock(); 970 try { 971 return m_controlWord.getTest() && m_controlWord.getEnabled(); 972 } finally { 973 m_cacheDataMutex.unlock(); 974 } 975 } 976 977 /** 978 * Gets a value indicating whether the Driver Station is attached. 979 * 980 * @return True if Driver Station is attached, false otherwise. 981 */ 982 public static boolean isDSAttached() { 983 m_cacheDataMutex.lock(); 984 try { 985 return m_controlWord.getDSAttached(); 986 } finally { 987 m_cacheDataMutex.unlock(); 988 } 989 } 990 991 /** 992 * Gets if the driver station attached to a Field Management System. 993 * 994 * @return true if the robot is competing on a field being controlled by a Field Management System 995 */ 996 public static boolean isFMSAttached() { 997 m_cacheDataMutex.lock(); 998 try { 999 return m_controlWord.getFMSAttached(); 1000 } finally { 1001 m_cacheDataMutex.unlock(); 1002 } 1003 } 1004 1005 /** 1006 * Get the game specific message from the FMS. 1007 * 1008 * <p>If the FMS is not connected, it is set from the game data setting on the driver station. 1009 * 1010 * @return the game specific message 1011 */ 1012 public static String getGameSpecificMessage() { 1013 m_cacheDataMutex.lock(); 1014 try { 1015 return m_matchInfo.gameSpecificMessage; 1016 } finally { 1017 m_cacheDataMutex.unlock(); 1018 } 1019 } 1020 1021 /** 1022 * Get the event name from the FMS. 1023 * 1024 * @return the event name 1025 */ 1026 public static String getEventName() { 1027 m_cacheDataMutex.lock(); 1028 try { 1029 return m_matchInfo.eventName; 1030 } finally { 1031 m_cacheDataMutex.unlock(); 1032 } 1033 } 1034 1035 /** 1036 * Get the match type from the FMS. 1037 * 1038 * @return the match type 1039 */ 1040 public static MatchType getMatchType() { 1041 int matchType; 1042 m_cacheDataMutex.lock(); 1043 try { 1044 matchType = m_matchInfo.matchType; 1045 } finally { 1046 m_cacheDataMutex.unlock(); 1047 } 1048 return switch (matchType) { 1049 case 1 -> MatchType.Practice; 1050 case 2 -> MatchType.Qualification; 1051 case 3 -> MatchType.Elimination; 1052 default -> MatchType.None; 1053 }; 1054 } 1055 1056 /** 1057 * Get the match number from the FMS. 1058 * 1059 * @return the match number 1060 */ 1061 public static int getMatchNumber() { 1062 m_cacheDataMutex.lock(); 1063 try { 1064 return m_matchInfo.matchNumber; 1065 } finally { 1066 m_cacheDataMutex.unlock(); 1067 } 1068 } 1069 1070 /** 1071 * Get the replay number from the FMS. 1072 * 1073 * @return the replay number 1074 */ 1075 public static int getReplayNumber() { 1076 m_cacheDataMutex.lock(); 1077 try { 1078 return m_matchInfo.replayNumber; 1079 } finally { 1080 m_cacheDataMutex.unlock(); 1081 } 1082 } 1083 1084 private static Map<AllianceStationID, Optional<Alliance>> m_allianceMap = 1085 Map.of( 1086 AllianceStationID.Unknown, Optional.empty(), 1087 AllianceStationID.Red1, Optional.of(Alliance.Red), 1088 AllianceStationID.Red2, Optional.of(Alliance.Red), 1089 AllianceStationID.Red3, Optional.of(Alliance.Red), 1090 AllianceStationID.Blue1, Optional.of(Alliance.Blue), 1091 AllianceStationID.Blue2, Optional.of(Alliance.Blue), 1092 AllianceStationID.Blue3, Optional.of(Alliance.Blue)); 1093 1094 private static Map<AllianceStationID, OptionalInt> m_stationMap = 1095 Map.of( 1096 AllianceStationID.Unknown, OptionalInt.empty(), 1097 AllianceStationID.Red1, OptionalInt.of(1), 1098 AllianceStationID.Red2, OptionalInt.of(2), 1099 AllianceStationID.Red3, OptionalInt.of(3), 1100 AllianceStationID.Blue1, OptionalInt.of(1), 1101 AllianceStationID.Blue2, OptionalInt.of(2), 1102 AllianceStationID.Blue3, OptionalInt.of(3)); 1103 1104 /** 1105 * Get the current alliance from the FMS. 1106 * 1107 * <p>If the FMS is not connected, it is set from the team alliance setting on the driver station. 1108 * 1109 * @return The alliance (red or blue) or an empty optional if the alliance is invalid 1110 */ 1111 public static Optional<Alliance> getAlliance() { 1112 AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation(); 1113 if (allianceStationID == null) { 1114 allianceStationID = AllianceStationID.Unknown; 1115 } 1116 1117 return m_allianceMap.get(allianceStationID); 1118 } 1119 1120 /** 1121 * Gets the location of the team's driver station controls from the FMS. 1122 * 1123 * <p>If the FMS is not connected, it is set from the team alliance setting on the driver station. 1124 * 1125 * @return the location of the team's driver station controls: 1, 2, or 3 1126 */ 1127 public static OptionalInt getLocation() { 1128 AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation(); 1129 if (allianceStationID == null) { 1130 allianceStationID = AllianceStationID.Unknown; 1131 } 1132 1133 return m_stationMap.get(allianceStationID); 1134 } 1135 1136 /** 1137 * Gets the raw alliance station of the teams driver station. 1138 * 1139 * <p>This returns the raw low level value. Prefer getLocation or getAlliance unless necessary for 1140 * performance. 1141 * 1142 * @return The raw alliance station id. 1143 */ 1144 public static AllianceStationID getRawAllianceStation() { 1145 return DriverStationJNI.getAllianceStation(); 1146 } 1147 1148 /** 1149 * Wait for a DS connection. 1150 * 1151 * @param timeoutSeconds timeout in seconds. 0 for infinite. 1152 * @return true if connected, false if timeout 1153 */ 1154 public static boolean waitForDsConnection(double timeoutSeconds) { 1155 int event = WPIUtilJNI.createEvent(true, false); 1156 DriverStationJNI.provideNewDataEventHandle(event); 1157 boolean result; 1158 try { 1159 if (timeoutSeconds == 0) { 1160 WPIUtilJNI.waitForObject(event); 1161 result = true; 1162 } else { 1163 result = !WPIUtilJNI.waitForObjectTimeout(event, timeoutSeconds); 1164 } 1165 } catch (InterruptedException ex) { 1166 Thread.currentThread().interrupt(); 1167 result = false; 1168 } finally { 1169 DriverStationJNI.removeNewDataEventHandle(event); 1170 WPIUtilJNI.destroyEvent(event); 1171 } 1172 return result; 1173 } 1174 1175 /** 1176 * Return the approximate match time. The FMS does not send an official match time to the robots, 1177 * but does send an approximate match time. The value will count down the time remaining in the 1178 * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to 1179 * dispute ref calls or guarantee that a function will trigger before the match ends). 1180 * 1181 * <p>When connected to the real field, this number only changes in full integer increments, and 1182 * always counts down. 1183 * 1184 * <p>When the DS is in practice mode, this number is a floating point number, and counts down. 1185 * 1186 * <p>When the DS is in teleop or autonomous mode, this number is a floating point number, and 1187 * counts up. 1188 * 1189 * <p>Simulation matches DS behavior without an FMS connected. 1190 * 1191 * @return Time remaining in current match period (auto or teleop) in seconds 1192 */ 1193 public static double getMatchTime() { 1194 return DriverStationJNI.getMatchTime(); 1195 } 1196 1197 /** 1198 * Allows the user to specify whether they want joystick connection warnings to be printed to the 1199 * console. This setting is ignored when the FMS is connected -- warnings will always be on in 1200 * that scenario. 1201 * 1202 * @param silence Whether warning messages should be silenced. 1203 */ 1204 public static void silenceJoystickConnectionWarning(boolean silence) { 1205 m_silenceJoystickWarning = silence; 1206 } 1207 1208 /** 1209 * Returns whether joystick connection warnings are silenced. This will always return false when 1210 * connected to the FMS. 1211 * 1212 * @return Whether joystick connection warnings are silenced. 1213 */ 1214 public static boolean isJoystickConnectionWarningSilenced() { 1215 return !isFMSAttached() && m_silenceJoystickWarning; 1216 } 1217 1218 /** 1219 * Refresh the passed in control word to contain the current control word cache. 1220 * 1221 * @param word Word to refresh. 1222 */ 1223 public static void refreshControlWordFromCache(ControlWord word) { 1224 m_cacheDataMutex.lock(); 1225 try { 1226 word.update(m_controlWord); 1227 } finally { 1228 m_cacheDataMutex.unlock(); 1229 } 1230 } 1231 1232 /** 1233 * Copy data from the DS task for the user. If no new data exists, it will just be returned, 1234 * otherwise the data will be copied from the DS polling loop. 1235 */ 1236 public static void refreshData() { 1237 DriverStationJNI.refreshDSData(); 1238 1239 // Get the status of all the joysticks 1240 for (byte stick = 0; stick < kJoystickPorts; stick++) { 1241 m_joystickAxesCache[stick].m_count = 1242 DriverStationJNI.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes); 1243 m_joystickAxesRawCache[stick].m_count = 1244 DriverStationJNI.getJoystickAxesRaw(stick, m_joystickAxesRawCache[stick].m_axes); 1245 m_joystickPOVsCache[stick].m_count = 1246 DriverStationJNI.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs); 1247 m_joystickButtonsCache[stick].m_buttons = 1248 DriverStationJNI.getJoystickButtons(stick, m_buttonCountBuffer); 1249 m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0); 1250 } 1251 1252 DriverStationJNI.getMatchInfo(m_matchInfoCache); 1253 1254 DriverStationJNI.getControlWord(m_controlWordCache); 1255 1256 DataLogSender dataLogSender; 1257 // lock joystick mutex to swap cache data 1258 m_cacheDataMutex.lock(); 1259 try { 1260 for (int i = 0; i < kJoystickPorts; i++) { 1261 // If buttons weren't pressed and are now, set flags in m_buttonsPressed 1262 m_joystickButtonsPressed[i] |= 1263 ~m_joystickButtons[i].m_buttons & m_joystickButtonsCache[i].m_buttons; 1264 1265 // If buttons were pressed and aren't now, set flags in m_buttonsReleased 1266 m_joystickButtonsReleased[i] |= 1267 m_joystickButtons[i].m_buttons & ~m_joystickButtonsCache[i].m_buttons; 1268 } 1269 1270 // move cache to actual data 1271 HALJoystickAxes[] currentAxes = m_joystickAxes; 1272 m_joystickAxes = m_joystickAxesCache; 1273 m_joystickAxesCache = currentAxes; 1274 1275 HALJoystickAxesRaw[] currentAxesRaw = m_joystickAxesRaw; 1276 m_joystickAxesRaw = m_joystickAxesRawCache; 1277 m_joystickAxesRawCache = currentAxesRaw; 1278 1279 HALJoystickButtons[] currentButtons = m_joystickButtons; 1280 m_joystickButtons = m_joystickButtonsCache; 1281 m_joystickButtonsCache = currentButtons; 1282 1283 HALJoystickPOVs[] currentPOVs = m_joystickPOVs; 1284 m_joystickPOVs = m_joystickPOVsCache; 1285 m_joystickPOVsCache = currentPOVs; 1286 1287 MatchInfoData currentInfo = m_matchInfo; 1288 m_matchInfo = m_matchInfoCache; 1289 m_matchInfoCache = currentInfo; 1290 1291 ControlWord currentWord = m_controlWord; 1292 m_controlWord = m_controlWordCache; 1293 m_controlWordCache = currentWord; 1294 1295 dataLogSender = m_dataLogSender; 1296 } finally { 1297 m_cacheDataMutex.unlock(); 1298 } 1299 1300 m_refreshEvents.wakeup(); 1301 1302 m_matchDataSender.sendMatchData(); 1303 if (dataLogSender != null) { 1304 dataLogSender.send(WPIUtilJNI.now()); 1305 } 1306 } 1307 1308 /** 1309 * Registers the given handle for DS data refresh notifications. 1310 * 1311 * @param handle The event handle. 1312 */ 1313 public static void provideRefreshedDataEventHandle(int handle) { 1314 m_refreshEvents.add(handle); 1315 } 1316 1317 /** 1318 * Unregisters the given handle from DS data refresh notifications. 1319 * 1320 * @param handle The event handle. 1321 */ 1322 public static void removeRefreshedDataEventHandle(int handle) { 1323 m_refreshEvents.remove(handle); 1324 } 1325 1326 /** 1327 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 1328 * the DS. 1329 */ 1330 private static void reportJoystickUnpluggedError(String message) { 1331 double currentTime = Timer.getTimestamp(); 1332 if (currentTime > m_nextMessageTime) { 1333 reportError(message, false); 1334 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 1335 } 1336 } 1337 1338 /** 1339 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 1340 * the DS. 1341 */ 1342 private static void reportJoystickUnpluggedWarning(String message) { 1343 if (isFMSAttached() || !m_silenceJoystickWarning) { 1344 double currentTime = Timer.getTimestamp(); 1345 if (currentTime > m_nextMessageTime) { 1346 reportWarning(message, false); 1347 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 1348 } 1349 } 1350 } 1351 1352 /** 1353 * Starts logging DriverStation data to data log. Repeated calls are ignored. 1354 * 1355 * @param log data log 1356 * @param logJoysticks if true, log joystick data 1357 */ 1358 @SuppressWarnings("PMD.NonThreadSafeSingleton") 1359 public static void startDataLog(DataLog log, boolean logJoysticks) { 1360 m_cacheDataMutex.lock(); 1361 try { 1362 if (m_dataLogSender == null) { 1363 m_dataLogSender = new DataLogSender(log, logJoysticks, WPIUtilJNI.now()); 1364 } 1365 } finally { 1366 m_cacheDataMutex.unlock(); 1367 } 1368 } 1369 1370 /** 1371 * Starts logging DriverStation data to data log, including joystick data. Repeated calls are 1372 * ignored. 1373 * 1374 * @param log data log 1375 */ 1376 public static void startDataLog(DataLog log) { 1377 startDataLog(log, true); 1378 } 1379}