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