001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2008-2018 FIRST. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj; 009 010import java.nio.ByteBuffer; 011import java.util.concurrent.TimeUnit; 012import java.util.concurrent.locks.Condition; 013import java.util.concurrent.locks.Lock; 014import java.util.concurrent.locks.ReentrantLock; 015 016import edu.wpi.first.networktables.NetworkTable; 017import edu.wpi.first.networktables.NetworkTableEntry; 018import edu.wpi.first.networktables.NetworkTableInstance; 019import edu.wpi.first.wpilibj.hal.AllianceStationID; 020import edu.wpi.first.wpilibj.hal.ControlWord; 021import edu.wpi.first.wpilibj.hal.HAL; 022import edu.wpi.first.wpilibj.hal.MatchInfoData; 023import edu.wpi.first.wpilibj.hal.PowerJNI; 024 025/** 026 * Provide access to the network communication data to / from the Driver Station. 027 */ 028public class DriverStation implements RobotState.Interface { 029 /** 030 * Number of Joystick Ports. 031 */ 032 public static final int kJoystickPorts = 6; 033 034 private class HALJoystickButtons { 035 public int m_buttons; 036 public byte m_count; 037 } 038 039 private class HALJoystickAxes { 040 public float[] m_axes; 041 public short m_count; 042 043 HALJoystickAxes(int count) { 044 m_axes = new float[count]; 045 } 046 } 047 048 private class HALJoystickPOVs { 049 public short[] m_povs; 050 public short m_count; 051 052 HALJoystickPOVs(int count) { 053 m_povs = new short[count]; 054 } 055 } 056 057 /** 058 * The robot alliance that the robot is a part of. 059 */ 060 public enum Alliance { 061 Red, Blue, Invalid 062 } 063 064 public enum MatchType { 065 None, Practice, Qualification, Elimination 066 } 067 068 private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0; 069 private double m_nextMessageTime = 0.0; 070 071 private static class DriverStationTask implements Runnable { 072 private DriverStation m_ds; 073 074 DriverStationTask(DriverStation ds) { 075 m_ds = ds; 076 } 077 078 public void run() { 079 m_ds.run(); 080 } 081 } /* DriverStationTask */ 082 083 private static class MatchDataSender { 084 @SuppressWarnings("MemberName") 085 NetworkTable table; 086 @SuppressWarnings("MemberName") 087 NetworkTableEntry typeMetadata; 088 @SuppressWarnings("MemberName") 089 NetworkTableEntry gameSpecificMessage; 090 @SuppressWarnings("MemberName") 091 NetworkTableEntry eventName; 092 @SuppressWarnings("MemberName") 093 NetworkTableEntry matchNumber; 094 @SuppressWarnings("MemberName") 095 NetworkTableEntry replayNumber; 096 @SuppressWarnings("MemberName") 097 NetworkTableEntry matchType; 098 @SuppressWarnings("MemberName") 099 NetworkTableEntry alliance; 100 @SuppressWarnings("MemberName") 101 NetworkTableEntry station; 102 @SuppressWarnings("MemberName") 103 NetworkTableEntry controlWord; 104 105 MatchDataSender() { 106 table = NetworkTableInstance.getDefault().getTable("FMSInfo"); 107 typeMetadata = table.getEntry(".type"); 108 typeMetadata.forceSetString("FMSInfo"); 109 gameSpecificMessage = table.getEntry("GameSpecificMessage"); 110 gameSpecificMessage.forceSetString(""); 111 eventName = table.getEntry("EventName"); 112 eventName.forceSetString(""); 113 matchNumber = table.getEntry("MatchNumber"); 114 matchNumber.forceSetDouble(0); 115 replayNumber = table.getEntry("ReplayNumber"); 116 replayNumber.forceSetDouble(0); 117 matchType = table.getEntry("MatchType"); 118 matchType.forceSetDouble(0); 119 alliance = table.getEntry("IsRedAlliance"); 120 alliance.forceSetBoolean(true); 121 station = table.getEntry("StationNumber"); 122 station.forceSetDouble(1); 123 controlWord = table.getEntry("FMSControlData"); 124 controlWord.forceSetDouble(0); 125 } 126 } 127 128 private static DriverStation instance = new DriverStation(); 129 130 // Joystick User Data 131 private HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts]; 132 private HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts]; 133 private HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts]; 134 private MatchInfoData m_matchInfo = new MatchInfoData(); 135 136 // Joystick Cached Data 137 private HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts]; 138 private HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts]; 139 private HALJoystickButtons[] m_joystickButtonsCache = new HALJoystickButtons[kJoystickPorts]; 140 private MatchInfoData m_matchInfoCache = new MatchInfoData(); 141 142 // Joystick button rising/falling edge flags 143 HALJoystickButtons[] m_joystickButtonsPressed = new HALJoystickButtons[kJoystickPorts]; 144 HALJoystickButtons[] m_joystickButtonsReleased = new HALJoystickButtons[kJoystickPorts]; 145 146 // preallocated byte buffer for button count 147 private ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1); 148 149 private MatchDataSender m_matchDataSender; 150 151 // Internal Driver Station thread 152 private Thread m_thread; 153 private volatile boolean m_threadKeepAlive = true; 154 155 private final Object m_cacheDataMutex; 156 157 private final Lock m_waitForDataMutex; 158 private final Condition m_waitForDataCond; 159 private int m_waitForDataCount; 160 161 // Robot state status variables 162 private boolean m_userInDisabled = false; 163 private boolean m_userInAutonomous = false; 164 private boolean m_userInTeleop = false; 165 private boolean m_userInTest = false; 166 167 // Control word variables 168 private final Object m_controlWordMutex; 169 private ControlWord m_controlWordCache; 170 private long m_lastControlWordUpdate; 171 172 /** 173 * Gets an instance of the DriverStation. 174 * 175 * @return The DriverStation. 176 */ 177 public static DriverStation getInstance() { 178 return DriverStation.instance; 179 } 180 181 /** 182 * DriverStation constructor. 183 * 184 * <p>The single DriverStation instance is created statically with the instance static member 185 * variable. 186 */ 187 private DriverStation() { 188 m_waitForDataCount = 0; 189 m_waitForDataMutex = new ReentrantLock(); 190 m_waitForDataCond = m_waitForDataMutex.newCondition(); 191 192 m_cacheDataMutex = new Object(); 193 for (int i = 0; i < kJoystickPorts; i++) { 194 m_joystickButtons[i] = new HALJoystickButtons(); 195 m_joystickAxes[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes); 196 m_joystickPOVs[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs); 197 198 m_joystickButtonsCache[i] = new HALJoystickButtons(); 199 m_joystickAxesCache[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes); 200 m_joystickPOVsCache[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs); 201 202 m_joystickButtonsPressed[i] = new HALJoystickButtons(); 203 m_joystickButtonsReleased[i] = new HALJoystickButtons(); 204 } 205 206 m_controlWordMutex = new Object(); 207 m_controlWordCache = new ControlWord(); 208 m_lastControlWordUpdate = 0; 209 210 m_matchDataSender = new MatchDataSender(); 211 212 m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation"); 213 m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2); 214 215 m_thread.start(); 216 } 217 218 /** 219 * Kill the thread. 220 */ 221 public void release() { 222 m_threadKeepAlive = false; 223 } 224 225 /** 226 * Report error to Driver Station. Optionally appends Stack trace 227 * to error message. 228 * 229 * @param printTrace If true, append stack trace to error string 230 */ 231 public static void reportError(String error, boolean printTrace) { 232 reportErrorImpl(true, 1, error, printTrace); 233 } 234 235 /** 236 * Report error to Driver Station. Appends provided stack trace 237 * to error message. 238 * 239 * @param stackTrace The stack trace to append 240 */ 241 public static void reportError(String error, StackTraceElement[] stackTrace) { 242 reportErrorImpl(true, 1, error, stackTrace); 243 } 244 245 /** 246 * Report warning to Driver Station. Optionally appends Stack 247 * trace to warning message. 248 * 249 * @param printTrace If true, append stack trace to warning string 250 */ 251 public static void reportWarning(String error, boolean printTrace) { 252 reportErrorImpl(false, 1, error, printTrace); 253 } 254 255 /** 256 * Report warning to Driver Station. Appends provided stack 257 * trace to warning message. 258 * 259 * @param stackTrace The stack trace to append 260 */ 261 public static void reportWarning(String error, StackTraceElement[] stackTrace) { 262 reportErrorImpl(false, 1, error, stackTrace); 263 } 264 265 private static void reportErrorImpl(boolean isError, int code, String error, boolean 266 printTrace) { 267 reportErrorImpl(isError, code, error, printTrace, Thread.currentThread().getStackTrace(), 3); 268 } 269 270 private static void reportErrorImpl(boolean isError, int code, String error, 271 StackTraceElement[] stackTrace) { 272 reportErrorImpl(isError, code, error, true, stackTrace, 0); 273 } 274 275 private static void reportErrorImpl(boolean isError, int code, String error, 276 boolean printTrace, StackTraceElement[] stackTrace, int stackTraceFirst) { 277 String locString; 278 if (stackTrace.length >= stackTraceFirst + 1) { 279 locString = stackTrace[stackTraceFirst].toString(); 280 } else { 281 locString = ""; 282 } 283 String traceString = ""; 284 if (printTrace) { 285 boolean haveLoc = false; 286 for (int i = stackTraceFirst; i < stackTrace.length; i++) { 287 String loc = stackTrace[i].toString(); 288 traceString += "\tat " + loc + "\n"; 289 // get first user function 290 if (!haveLoc && !loc.startsWith("edu.wpi.first")) { 291 locString = loc; 292 haveLoc = true; 293 } 294 } 295 } 296 HAL.sendError(isError, code, false, error, locString, traceString, true); 297 } 298 299 /** 300 * The state of one joystick button. Button indexes begin at 1. 301 * 302 * @param stick The joystick to read. 303 * @param button The button index, beginning at 1. 304 * @return The state of the joystick button. 305 */ 306 public boolean getStickButton(final int stick, final int button) { 307 if (button <= 0) { 308 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 309 return false; 310 } 311 if (stick < 0 || stick >= kJoystickPorts) { 312 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 313 } 314 boolean error = false; 315 boolean retVal = false; 316 synchronized (m_cacheDataMutex) { 317 if (button > m_joystickButtons[stick].m_count) { 318 error = true; 319 retVal = false; 320 } else { 321 retVal = (m_joystickButtons[stick].m_buttons & 1 << (button - 1)) != 0; 322 } 323 } 324 if (error) { 325 reportJoystickUnpluggedWarning("Joystick Button " + button + " on port " + stick 326 + " not available, check if controller is plugged in"); 327 } 328 return retVal; 329 } 330 331 /** 332 * Whether one joystick button was pressed since the last check. Button indexes begin at 1. 333 * 334 * @param stick The joystick to read. 335 * @param button The button index, beginning at 1. 336 * @return Whether the joystick button was pressed since the last check. 337 */ 338 boolean getStickButtonPressed(final int stick, final int button) { 339 if (button <= 0) { 340 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 341 return false; 342 } 343 if (stick < 0 || stick >= kJoystickPorts) { 344 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 345 } 346 347 // If button was pressed, clear flag and return true 348 if ((m_joystickButtonsPressed[stick].m_buttons & 1 << (button - 1)) != 0) { 349 m_joystickButtonsPressed[stick].m_buttons &= ~(1 << (button - 1)); 350 return true; 351 } else { 352 return false; 353 } 354 } 355 356 /** 357 * Whether one joystick button was released since the last check. Button indexes 358 * begin at 1. 359 * 360 * @param stick The joystick to read. 361 * @param button The button index, beginning at 1. 362 * @return Whether the joystick button was released since the last check. 363 */ 364 boolean getStickButtonReleased(final int stick, final int button) { 365 if (button <= 0) { 366 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 367 return false; 368 } 369 if (stick < 0 || stick >= kJoystickPorts) { 370 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 371 } 372 373 // If button was released, clear flag and return true 374 if ((m_joystickButtonsReleased[stick].m_buttons & 1 << (button - 1)) != 0) { 375 m_joystickButtonsReleased[stick].m_buttons &= ~(1 << (button - 1)); 376 return true; 377 } else { 378 return false; 379 } 380 } 381 382 /** 383 * Get the value of the axis on a joystick. This depends on the mapping of the joystick connected 384 * to the specified port. 385 * 386 * @param stick The joystick to read. 387 * @param axis The analog axis value to read from the joystick. 388 * @return The value of the axis on the joystick. 389 */ 390 public double getStickAxis(int stick, int axis) { 391 if (stick < 0 || stick >= kJoystickPorts) { 392 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 393 } 394 if (axis < 0 || axis >= HAL.kMaxJoystickAxes) { 395 throw new RuntimeException("Joystick axis is out of range"); 396 } 397 398 boolean error = false; 399 double retVal = 0.0; 400 synchronized (m_cacheDataMutex) { 401 if (axis >= m_joystickAxes[stick].m_count) { 402 // set error 403 error = true; 404 retVal = 0.0; 405 } else { 406 retVal = m_joystickAxes[stick].m_axes[axis]; 407 } 408 } 409 if (error) { 410 reportJoystickUnpluggedWarning("Joystick axis " + axis + " on port " + stick 411 + " not available, check if controller is plugged in"); 412 } 413 return retVal; 414 } 415 416 /** 417 * Get the state of a POV on the joystick. 418 * 419 * @return the angle of the POV in degrees, or -1 if the POV is not pressed. 420 */ 421 public int getStickPOV(int stick, int pov) { 422 if (stick < 0 || stick >= kJoystickPorts) { 423 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 424 } 425 if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) { 426 throw new RuntimeException("Joystick POV is out of range"); 427 } 428 boolean error = false; 429 int retVal = -1; 430 synchronized (m_cacheDataMutex) { 431 if (pov >= m_joystickPOVs[stick].m_count) { 432 error = true; 433 retVal = -1; 434 } else { 435 retVal = m_joystickPOVs[stick].m_povs[pov]; 436 } 437 } 438 if (error) { 439 reportJoystickUnpluggedWarning("Joystick POV " + pov + " on port " + stick 440 + " not available, check if controller is plugged in"); 441 } 442 return retVal; 443 } 444 445 /** 446 * The state of the buttons on the joystick. 447 * 448 * @param stick The joystick to read. 449 * @return The state of the buttons on the joystick. 450 */ 451 public int getStickButtons(final int stick) { 452 if (stick < 0 || stick >= kJoystickPorts) { 453 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 454 } 455 synchronized (m_cacheDataMutex) { 456 return m_joystickButtons[stick].m_buttons; 457 } 458 } 459 460 /** 461 * Returns the number of axes on a given joystick port. 462 * 463 * @param stick The joystick port number 464 * @return The number of axes on the indicated joystick 465 */ 466 public int getStickAxisCount(int stick) { 467 if (stick < 0 || stick >= kJoystickPorts) { 468 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 469 } 470 synchronized (m_cacheDataMutex) { 471 return m_joystickAxes[stick].m_count; 472 } 473 } 474 475 /** 476 * Returns the number of POVs on a given joystick port. 477 * 478 * @param stick The joystick port number 479 * @return The number of POVs on the indicated joystick 480 */ 481 public int getStickPOVCount(int stick) { 482 if (stick < 0 || stick >= kJoystickPorts) { 483 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 484 } 485 synchronized (m_cacheDataMutex) { 486 return m_joystickPOVs[stick].m_count; 487 } 488 } 489 490 /** 491 * Gets the number of buttons on a joystick. 492 * 493 * @param stick The joystick port number 494 * @return The number of buttons on the indicated joystick 495 */ 496 public int getStickButtonCount(int stick) { 497 if (stick < 0 || stick >= kJoystickPorts) { 498 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 499 } 500 synchronized (m_cacheDataMutex) { 501 return m_joystickButtons[stick].m_count; 502 } 503 } 504 505 /** 506 * Gets the value of isXbox on a joystick. 507 * 508 * @param stick The joystick port number 509 * @return A boolean that returns the value of isXbox 510 */ 511 public boolean getJoystickIsXbox(int stick) { 512 if (stick < 0 || stick >= kJoystickPorts) { 513 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 514 } 515 boolean error = false; 516 boolean retVal = false; 517 synchronized (m_cacheDataMutex) { 518 // TODO: Remove this when calling for descriptor on empty stick no longer 519 // crashes 520 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 521 error = true; 522 retVal = false; 523 } else if (HAL.getJoystickIsXbox((byte) stick) == 1) { 524 retVal = true; 525 } 526 } 527 if (error) { 528 reportJoystickUnpluggedWarning("Joystick on port " + stick 529 + " not available, check if controller is plugged in"); 530 } 531 return retVal; 532 } 533 534 /** 535 * Gets the value of type on a joystick. 536 * 537 * @param stick The joystick port number 538 * @return The value of type 539 */ 540 public int getJoystickType(int stick) { 541 if (stick < 0 || stick >= kJoystickPorts) { 542 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 543 } 544 boolean error = false; 545 int retVal = -1; 546 synchronized (m_cacheDataMutex) { 547 // TODO: Remove this when calling for descriptor on empty stick no longer 548 // crashes 549 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 550 error = true; 551 retVal = -1; 552 } else { 553 retVal = HAL.getJoystickType((byte) stick); 554 } 555 } 556 if (error) { 557 reportJoystickUnpluggedWarning("Joystick on port " + stick 558 + " not available, check if controller is plugged in"); 559 } 560 return retVal; 561 } 562 563 /** 564 * Gets the name of the joystick at a port. 565 * 566 * @param stick The joystick port number 567 * @return The value of name 568 */ 569 public String getJoystickName(int stick) { 570 if (stick < 0 || stick >= kJoystickPorts) { 571 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 572 } 573 boolean error = false; 574 String retVal = ""; 575 synchronized (m_cacheDataMutex) { 576 // TODO: Remove this when calling for descriptor on empty stick no longer 577 // crashes 578 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 579 error = true; 580 retVal = ""; 581 } else { 582 retVal = HAL.getJoystickName((byte) stick); 583 } 584 } 585 if (error) { 586 reportJoystickUnpluggedWarning("Joystick on port " + stick 587 + " not available, check if controller is plugged in"); 588 } 589 return retVal; 590 } 591 592 /** 593 * Returns the types of Axes on a given joystick port. 594 * 595 * @param stick The joystick port number 596 * @param axis The target axis 597 * @return What type of axis the axis is reporting to be 598 */ 599 public int getJoystickAxisType(int stick, int axis) { 600 if (stick < 0 || stick >= kJoystickPorts) { 601 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 602 } 603 604 int retVal = -1; 605 synchronized (m_cacheDataMutex) { 606 retVal = HAL.getJoystickAxisType((byte) stick, (byte) axis); 607 } 608 return retVal; 609 } 610 611 /** 612 * Gets a value indicating whether the Driver Station requires the robot to be enabled. 613 * 614 * @return True if the robot is enabled, false otherwise. 615 */ 616 public boolean isEnabled() { 617 synchronized (m_controlWordMutex) { 618 updateControlWord(false); 619 return m_controlWordCache.getEnabled() && m_controlWordCache.getDSAttached(); 620 } 621 } 622 623 /** 624 * Gets a value indicating whether the Driver Station requires the robot to be disabled. 625 * 626 * @return True if the robot should be disabled, false otherwise. 627 */ 628 public boolean isDisabled() { 629 return !isEnabled(); 630 } 631 632 /** 633 * Gets a value indicating whether the Driver Station requires the robot to be running in 634 * autonomous mode. 635 * 636 * @return True if autonomous mode should be enabled, false otherwise. 637 */ 638 public boolean isAutonomous() { 639 synchronized (m_controlWordMutex) { 640 updateControlWord(false); 641 return m_controlWordCache.getAutonomous(); 642 } 643 } 644 645 /** 646 * Gets a value indicating whether the Driver Station requires the robot to be running in 647 * operator-controlled mode. 648 * 649 * @return True if operator-controlled mode should be enabled, false otherwise. 650 */ 651 public boolean isOperatorControl() { 652 return !(isAutonomous() || isTest()); 653 } 654 655 /** 656 * Gets a value indicating whether the Driver Station requires the robot to be running in test 657 * mode. 658 * 659 * @return True if test mode should be enabled, false otherwise. 660 */ 661 public boolean isTest() { 662 synchronized (m_controlWordMutex) { 663 updateControlWord(false); 664 return m_controlWordCache.getTest(); 665 } 666 } 667 668 /** 669 * Gets a value indicating whether the Driver Station is attached. 670 * 671 * @return True if Driver Station is attached, false otherwise. 672 */ 673 public boolean isDSAttached() { 674 synchronized (m_controlWordMutex) { 675 updateControlWord(false); 676 return m_controlWordCache.getDSAttached(); 677 } 678 } 679 680 /** 681 * Gets if a new control packet from the driver station arrived since the last time this function 682 * was called. 683 * 684 * @return True if the control data has been updated since the last call. 685 */ 686 public boolean isNewControlData() { 687 return HAL.isNewControlData(); 688 } 689 690 /** 691 * Gets if the driver station attached to a Field Management System. 692 * 693 * @return true if the robot is competing on a field being controlled by a Field Management System 694 */ 695 public boolean isFMSAttached() { 696 synchronized (m_controlWordMutex) { 697 updateControlWord(false); 698 return m_controlWordCache.getFMSAttached(); 699 } 700 } 701 702 /** 703 * Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled if 704 * the robot is disabled or e-stopped, the watchdog has expired, or if the roboRIO browns out. 705 * 706 * @return True if the FPGA outputs are enabled. 707 * @deprecated Use RobotController.isSysActive() 708 */ 709 @Deprecated 710 public boolean isSysActive() { 711 return HAL.getSystemActive(); 712 } 713 714 /** 715 * Check if the system is browned out. 716 * 717 * @return True if the system is browned out 718 * @deprecated Use RobotController.isBrownedOut() 719 */ 720 @Deprecated 721 public boolean isBrownedOut() { 722 return HAL.getBrownedOut(); 723 } 724 725 /** 726 * Get the game specific message. 727 * 728 * @return the game specific message 729 */ 730 public String getGameSpecificMessage() { 731 synchronized (m_cacheDataMutex) { 732 return m_matchInfo.gameSpecificMessage; 733 } 734 } 735 736 /** 737 * Get the event name. 738 * 739 * @return the event name 740 */ 741 public String getEventName() { 742 synchronized (m_cacheDataMutex) { 743 return m_matchInfo.eventName; 744 } 745 } 746 747 /** 748 * Get the match type. 749 * 750 * @return the match type 751 */ 752 public MatchType getMatchType() { 753 int matchType; 754 synchronized (m_cacheDataMutex) { 755 matchType = m_matchInfo.matchType; 756 } 757 switch (matchType) { 758 case 1: 759 return MatchType.Practice; 760 case 2: 761 return MatchType.Qualification; 762 case 3: 763 return MatchType.Elimination; 764 default: 765 return MatchType.None; 766 } 767 } 768 769 /** 770 * Get the match number. 771 * 772 * @return the match number 773 */ 774 public int getMatchNumber() { 775 synchronized (m_cacheDataMutex) { 776 return m_matchInfo.matchNumber; 777 } 778 } 779 780 /** 781 * Get the replay number. 782 * 783 * @return the replay number 784 */ 785 public int getReplayNumber() { 786 synchronized (m_cacheDataMutex) { 787 return m_matchInfo.replayNumber; 788 } 789 } 790 791 /** 792 * Get the current alliance from the FMS. 793 * 794 * @return the current alliance 795 */ 796 public Alliance getAlliance() { 797 AllianceStationID allianceStationID = HAL.getAllianceStation(); 798 if (allianceStationID == null) { 799 return Alliance.Invalid; 800 } 801 802 switch (allianceStationID) { 803 case Red1: 804 case Red2: 805 case Red3: 806 return Alliance.Red; 807 808 case Blue1: 809 case Blue2: 810 case Blue3: 811 return Alliance.Blue; 812 813 default: 814 return Alliance.Invalid; 815 } 816 } 817 818 /** 819 * Gets the location of the team's driver station controls. 820 * 821 * @return the location of the team's driver station controls: 1, 2, or 3 822 */ 823 public int getLocation() { 824 AllianceStationID allianceStationID = HAL.getAllianceStation(); 825 if (allianceStationID == null) { 826 return 0; 827 } 828 switch (allianceStationID) { 829 case Red1: 830 case Blue1: 831 return 1; 832 833 case Red2: 834 case Blue2: 835 return 2; 836 837 case Blue3: 838 case Red3: 839 return 3; 840 841 default: 842 return 0; 843 } 844 } 845 846 /** 847 * Wait for new data from the driver station. 848 */ 849 public void waitForData() { 850 waitForData(0); 851 } 852 853 /** 854 * Wait for new data or for timeout, which ever comes first. If timeout is 0, wait for new data 855 * only. 856 * 857 * @param timeout The maximum time in seconds to wait. 858 * @return true if there is new data, otherwise false 859 */ 860 public boolean waitForData(double timeout) { 861 long startTime = RobotController.getFPGATime(); 862 long timeoutMicros = (long) (timeout * 1000000); 863 m_waitForDataMutex.lock(); 864 try { 865 int currentCount = m_waitForDataCount; 866 while (m_waitForDataCount == currentCount) { 867 if (timeout > 0) { 868 long now = RobotController.getFPGATime(); 869 if (now < startTime + timeoutMicros) { 870 // We still have time to wait 871 boolean signaled = m_waitForDataCond.await(startTime + timeoutMicros - now, 872 TimeUnit.MICROSECONDS); 873 if (!signaled) { 874 // Return false if a timeout happened 875 return false; 876 } 877 } else { 878 // Time has elapsed. 879 return false; 880 } 881 } else { 882 m_waitForDataCond.await(); 883 } 884 } 885 // Return true if we have received a proper signal 886 return true; 887 } catch (InterruptedException ex) { 888 // return false on a thread interrupt 889 return false; 890 } finally { 891 m_waitForDataMutex.unlock(); 892 } 893 } 894 895 /** 896 * Return the approximate match time. The FMS does not send an official match time to the robots, 897 * but does send an approximate match time. The value will count down the time remaining in the 898 * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to 899 * dispute ref calls or guarantee that a function will trigger before the match ends) The 900 * Practice Match function of the DS approximates the behaviour seen on the field. 901 * 902 * @return Time remaining in current match period (auto or teleop) in seconds 903 */ 904 public double getMatchTime() { 905 return HAL.getMatchTime(); 906 } 907 908 /** 909 * Read the battery voltage. 910 * 911 * @return The battery voltage in Volts. 912 * @deprecated Use RobotController.getBatteryVoltage 913 */ 914 @Deprecated 915 public double getBatteryVoltage() { 916 return PowerJNI.getVinVoltage(); 917 } 918 919 /** 920 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 921 * purposes only. 922 * 923 * @param entering If true, starting disabled code; if false, leaving disabled code 924 */ 925 @SuppressWarnings("MethodName") 926 public void InDisabled(boolean entering) { 927 m_userInDisabled = entering; 928 } 929 930 /** 931 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 932 * purposes only. 933 * 934 * @param entering If true, starting autonomous code; if false, leaving autonomous code 935 */ 936 @SuppressWarnings("MethodName") 937 public void InAutonomous(boolean entering) { 938 m_userInAutonomous = entering; 939 } 940 941 /** 942 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 943 * purposes only. 944 * 945 * @param entering If true, starting teleop code; if false, leaving teleop code 946 */ 947 @SuppressWarnings("MethodName") 948 public void InOperatorControl(boolean entering) { 949 m_userInTeleop = entering; 950 } 951 952 /** 953 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 954 * purposes only. 955 * 956 * @param entering If true, starting test code; if false, leaving test code 957 */ 958 @SuppressWarnings("MethodName") 959 public void InTest(boolean entering) { 960 m_userInTest = entering; 961 } 962 963 private void sendMatchData() { 964 AllianceStationID alliance = HAL.getAllianceStation(); 965 boolean isRedAlliance = false; 966 int stationNumber = 1; 967 switch (alliance) { 968 case Blue1: 969 isRedAlliance = false; 970 stationNumber = 1; 971 break; 972 case Blue2: 973 isRedAlliance = false; 974 stationNumber = 2; 975 break; 976 case Blue3: 977 isRedAlliance = false; 978 stationNumber = 3; 979 break; 980 case Red1: 981 isRedAlliance = true; 982 stationNumber = 1; 983 break; 984 case Red2: 985 isRedAlliance = true; 986 stationNumber = 2; 987 break; 988 default: 989 isRedAlliance = true; 990 stationNumber = 3; 991 break; 992 } 993 994 995 String eventName; 996 String gameSpecificMessage; 997 int matchNumber; 998 int replayNumber; 999 int matchType; 1000 synchronized (m_cacheDataMutex) { 1001 eventName = m_matchInfo.eventName; 1002 gameSpecificMessage = m_matchInfo.gameSpecificMessage; 1003 matchNumber = m_matchInfo.matchNumber; 1004 replayNumber = m_matchInfo.replayNumber; 1005 matchType = m_matchInfo.matchType; 1006 } 1007 1008 m_matchDataSender.alliance.setBoolean(isRedAlliance); 1009 m_matchDataSender.station.setDouble(stationNumber); 1010 m_matchDataSender.eventName.setString(eventName); 1011 m_matchDataSender.gameSpecificMessage.setString(gameSpecificMessage); 1012 m_matchDataSender.matchNumber.setDouble(matchNumber); 1013 m_matchDataSender.replayNumber.setDouble(replayNumber); 1014 m_matchDataSender.matchType.setDouble(matchType); 1015 m_matchDataSender.controlWord.setDouble(HAL.nativeGetControlWord()); 1016 } 1017 1018 /** 1019 * Copy data from the DS task for the user. If no new data exists, it will just be returned, 1020 * otherwise the data will be copied from the DS polling loop. 1021 */ 1022 protected void getData() { 1023 // Get the status of all of the joysticks 1024 for (byte stick = 0; stick < kJoystickPorts; stick++) { 1025 m_joystickAxesCache[stick].m_count = 1026 HAL.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes); 1027 m_joystickPOVsCache[stick].m_count = 1028 HAL.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs); 1029 m_joystickButtonsCache[stick].m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer); 1030 m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0); 1031 } 1032 1033 HAL.getMatchInfo(m_matchInfoCache); 1034 1035 // Force a control word update, to make sure the data is the newest. 1036 updateControlWord(true); 1037 1038 // lock joystick mutex to swap cache data 1039 synchronized (m_cacheDataMutex) { 1040 for (int i = 0; i < kJoystickPorts; i++) { 1041 // If buttons weren't pressed and are now, set flags in m_buttonsPressed 1042 m_joystickButtonsPressed[i].m_buttons |= 1043 ~m_joystickButtons[i].m_buttons & m_joystickButtonsCache[i].m_buttons; 1044 1045 // If buttons were pressed and aren't now, set flags in m_buttonsReleased 1046 m_joystickButtonsReleased[i].m_buttons |= 1047 m_joystickButtons[i].m_buttons & ~m_joystickButtonsCache[i].m_buttons; 1048 } 1049 1050 // move cache to actual data 1051 HALJoystickAxes[] currentAxes = m_joystickAxes; 1052 m_joystickAxes = m_joystickAxesCache; 1053 m_joystickAxesCache = currentAxes; 1054 1055 HALJoystickButtons[] currentButtons = m_joystickButtons; 1056 m_joystickButtons = m_joystickButtonsCache; 1057 m_joystickButtonsCache = currentButtons; 1058 1059 HALJoystickPOVs[] currentPOVs = m_joystickPOVs; 1060 m_joystickPOVs = m_joystickPOVsCache; 1061 m_joystickPOVsCache = currentPOVs; 1062 1063 MatchInfoData currentInfo = m_matchInfo; 1064 m_matchInfo = m_matchInfoCache; 1065 m_matchInfoCache = currentInfo; 1066 } 1067 1068 m_waitForDataMutex.lock(); 1069 m_waitForDataCount++; 1070 m_waitForDataCond.signalAll(); 1071 m_waitForDataMutex.unlock(); 1072 1073 sendMatchData(); 1074 } 1075 1076 /** 1077 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 1078 * the DS. 1079 */ 1080 private void reportJoystickUnpluggedError(String message) { 1081 double currentTime = Timer.getFPGATimestamp(); 1082 if (currentTime > m_nextMessageTime) { 1083 reportError(message, false); 1084 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 1085 } 1086 } 1087 1088 /** 1089 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 1090 * the DS. 1091 */ 1092 private void reportJoystickUnpluggedWarning(String message) { 1093 double currentTime = Timer.getFPGATimestamp(); 1094 if (currentTime > m_nextMessageTime) { 1095 reportWarning(message, false); 1096 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 1097 } 1098 } 1099 1100 /** 1101 * Provides the service routine for the DS polling m_thread. 1102 */ 1103 private void run() { 1104 int safetyCounter = 0; 1105 while (m_threadKeepAlive) { 1106 HAL.waitForDSData(); 1107 getData(); 1108 1109 if (isDisabled()) { 1110 safetyCounter = 0; 1111 } 1112 1113 if (++safetyCounter >= 4) { 1114 MotorSafetyHelper.checkMotors(); 1115 safetyCounter = 0; 1116 } 1117 if (m_userInDisabled) { 1118 HAL.observeUserProgramDisabled(); 1119 } 1120 if (m_userInAutonomous) { 1121 HAL.observeUserProgramAutonomous(); 1122 } 1123 if (m_userInTeleop) { 1124 HAL.observeUserProgramTeleop(); 1125 } 1126 if (m_userInTest) { 1127 HAL.observeUserProgramTest(); 1128 } 1129 } 1130 } 1131 1132 /** 1133 * Updates the data in the control word cache. Updates if the force parameter is set, or if 1134 * 50ms have passed since the last update. 1135 * 1136 * @param force True to force an update to the cache, otherwise update if 50ms have passed. 1137 */ 1138 private void updateControlWord(boolean force) { 1139 long now = System.currentTimeMillis(); 1140 synchronized (m_controlWordMutex) { 1141 if (now - m_lastControlWordUpdate > 50 || force) { 1142 HAL.getControlWord(m_controlWordCache); 1143 m_lastControlWordUpdate = now; 1144 } 1145 } 1146 } 1147}