001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) FIRST 2008-2017. 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; 011 012import java.util.concurrent.TimeUnit; 013import java.util.concurrent.locks.Condition; 014import java.util.concurrent.locks.Lock; 015import java.util.concurrent.locks.ReentrantLock; 016import java.util.concurrent.atomic.AtomicBoolean; 017 018import edu.wpi.first.wpilibj.hal.AllianceStationID; 019import edu.wpi.first.wpilibj.hal.ControlWord; 020import edu.wpi.first.wpilibj.hal.HAL; 021import edu.wpi.first.wpilibj.hal.PowerJNI; 022 023/** 024 * Provide access to the network communication data to / from the Driver Station. 025 */ 026public class DriverStation implements RobotState.Interface { 027 028 /** 029 * Number of Joystick Ports. 030 */ 031 public static final int kJoystickPorts = 6; 032 033 private class HALJoystickButtons { 034 public int m_buttons; 035 public byte m_count; 036 } 037 038 private class HALJoystickAxes { 039 public float[] m_axes; 040 public short m_count; 041 042 public HALJoystickAxes(int count) { 043 m_axes = new float[count]; 044 } 045 } 046 047 private class HALJoystickPOVs { 048 public short[] m_povs; 049 public short m_count; 050 051 public HALJoystickPOVs(int count) { 052 m_povs = new short[count]; 053 } 054 } 055 056 /** 057 * The robot alliance that the robot is a part of. 058 */ 059 public enum Alliance { 060 Red, Blue, Invalid 061 } 062 063 private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0; 064 private double m_nextMessageTime = 0.0; 065 066 private static class DriverStationTask implements Runnable { 067 068 private DriverStation m_ds; 069 070 DriverStationTask(DriverStation ds) { 071 m_ds = ds; 072 } 073 074 public void run() { 075 m_ds.run(); 076 } 077 } /* DriverStationTask */ 078 079 private static DriverStation instance = new DriverStation(); 080 081 // Joystick User Data 082 private HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[kJoystickPorts]; 083 private HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[kJoystickPorts]; 084 private HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[kJoystickPorts]; 085 086 // Joystick Cached Data 087 private HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[kJoystickPorts]; 088 private HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[kJoystickPorts]; 089 private HALJoystickButtons[] m_joystickButtonsCache = new HALJoystickButtons[kJoystickPorts]; 090 // preallocated byte buffer for button count 091 private ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1); 092 093 // Internal Driver Station thread 094 private Thread m_thread; 095 096 private final Lock m_dataMutex; 097 private final Condition m_dataCond; 098 099 private volatile boolean m_threadKeepAlive = true; 100 101 // WPILib WaitForData control variables 102 private boolean m_waitForDataPredicate; 103 104 private AtomicBoolean m_newControlData; 105 106 private final Object m_joystickMutex; 107 108 // Robot state status variables 109 private boolean m_userInDisabled = false; 110 private boolean m_userInAutonomous = false; 111 private boolean m_userInTeleop = false; 112 private boolean m_userInTest = false; 113 114 // Control word variables 115 private final Object m_controlWordMutex; 116 private ControlWord m_controlWordCache; 117 private long m_lastControlWordUpdate; 118 119 /** 120 * Gets an instance of the DriverStation 121 * 122 * @return The DriverStation. 123 */ 124 public static DriverStation getInstance() { 125 return DriverStation.instance; 126 } 127 128 /** 129 * DriverStation constructor. 130 * 131 * <p>The single DriverStation instance is created statically with the instance static member 132 * variable. 133 */ 134 private DriverStation() { 135 m_dataMutex = new ReentrantLock(); 136 m_dataCond = m_dataMutex.newCondition(); 137 m_joystickMutex = new Object(); 138 m_newControlData = new AtomicBoolean(false); 139 for (int i = 0; i < kJoystickPorts; i++) { 140 m_joystickButtons[i] = new HALJoystickButtons(); 141 m_joystickAxes[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes); 142 m_joystickPOVs[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs); 143 144 m_joystickButtonsCache[i] = new HALJoystickButtons(); 145 m_joystickAxesCache[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes); 146 m_joystickPOVsCache[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs); 147 } 148 149 m_controlWordMutex = new Object(); 150 m_controlWordCache = new ControlWord(); 151 m_lastControlWordUpdate = 0; 152 153 m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation"); 154 m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2); 155 156 m_thread.start(); 157 } 158 159 /** 160 * Kill the thread. 161 */ 162 public void release() { 163 m_threadKeepAlive = false; 164 } 165 166 /** 167 * Report error to Driver Station. Also prints error to System.err Optionally appends Stack trace 168 * to error message. 169 * 170 * @param printTrace If true, append stack trace to error string 171 */ 172 public static void reportError(String error, boolean printTrace) { 173 reportErrorImpl(true, 1, error, printTrace); 174 } 175 176 /** 177 * Report warning to Driver Station. Also prints error to System.err Optionally appends Stack 178 * trace to warning message. 179 * 180 * @param printTrace If true, append stack trace to warning string 181 */ 182 public static void reportWarning(String error, boolean printTrace) { 183 reportErrorImpl(false, 1, error, printTrace); 184 } 185 186 private static void reportErrorImpl(boolean isError, int code, String error, boolean 187 printTrace) { 188 StackTraceElement[] traces = Thread.currentThread().getStackTrace(); 189 String locString; 190 if (traces.length > 3) { 191 locString = traces[3].toString(); 192 } else { 193 locString = ""; 194 } 195 boolean haveLoc = false; 196 String traceString = " at "; 197 for (int i = 3; i < traces.length; i++) { 198 String loc = traces[i].toString(); 199 traceString += loc + "\n"; 200 // get first user function 201 if (!haveLoc && !loc.startsWith("edu.wpi.first.wpilibj")) { 202 locString = loc; 203 haveLoc = true; 204 } 205 } 206 HAL.sendError(isError, code, false, error, locString, printTrace ? traceString : "", true); 207 } 208 209 /** 210 * Get the value of the axis on a joystick. This depends on the mapping of the joystick connected 211 * to the specified port. 212 * 213 * @param stick The joystick to read. 214 * @param axis The analog axis value to read from the joystick. 215 * @return The value of the axis on the joystick. 216 */ 217 public double getStickAxis(int stick, int axis) { 218 if (stick < 0 || stick >= kJoystickPorts) { 219 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 220 } 221 if (axis < 0 || axis >= HAL.kMaxJoystickAxes) { 222 throw new RuntimeException("Joystick axis is out of range"); 223 } 224 225 boolean error = false; 226 double retVal = 0.0; 227 synchronized (m_joystickMutex) { 228 if (axis >= m_joystickAxes[stick].m_count) { 229 // set error 230 error = true; 231 retVal = 0.0; 232 } else { 233 retVal = m_joystickAxes[stick].m_axes[axis]; 234 } 235 } 236 if (error) { 237 reportJoystickUnpluggedWarning("Joystick axis " + axis + " on port " + stick 238 + " not available, check if controller is plugged in"); 239 } 240 return retVal; 241 } 242 243 /** 244 * Get the state of a POV on the joystick. 245 * 246 * @return the angle of the POV in degrees, or -1 if the POV is not pressed. 247 */ 248 public int getStickPOV(int stick, int pov) { 249 if (stick < 0 || stick >= kJoystickPorts) { 250 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 251 } 252 if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) { 253 throw new RuntimeException("Joystick POV is out of range"); 254 } 255 boolean error = false; 256 int retVal = -1; 257 synchronized (m_joystickMutex) { 258 if (pov >= m_joystickPOVs[stick].m_count) { 259 error = true; 260 retVal = -1; 261 } else { 262 retVal = m_joystickPOVs[stick].m_povs[pov]; 263 } 264 } 265 if (error) { 266 reportJoystickUnpluggedWarning("Joystick POV " + pov + " on port " + stick 267 + " not available, check if controller is plugged in"); 268 } 269 return retVal; 270 } 271 272 /** 273 * The state of the buttons on the joystick. 274 * 275 * @param stick The joystick to read. 276 * @return The state of the buttons on the joystick. 277 */ 278 public int getStickButtons(final int stick) { 279 if (stick < 0 || stick >= kJoystickPorts) { 280 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 281 } 282 synchronized (m_joystickMutex) { 283 return m_joystickButtons[stick].m_buttons; 284 } 285 } 286 287 /** 288 * The state of one joystick button. Button indexes begin at 1. 289 * 290 * @param stick The joystick to read. 291 * @param button The button index, beginning at 1. 292 * @return The state of the joystick button. 293 */ 294 public boolean getStickButton(final int stick, byte button) { 295 if (button <= 0) { 296 reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n"); 297 return false; 298 } 299 if (stick < 0 || stick >= kJoystickPorts) { 300 throw new RuntimeException("Joystick index is out of range, should be 0-3"); 301 } 302 boolean error = false; 303 boolean retVal = false; 304 synchronized (m_joystickMutex) { 305 if (button > m_joystickButtons[stick].m_count) { 306 error = true; 307 retVal = false; 308 } else { 309 retVal = ((0x1 << (button - 1)) & m_joystickButtons[stick].m_buttons) != 0; 310 } 311 } 312 if (error) { 313 reportJoystickUnpluggedWarning("Joystick Button " + button + " on port " + stick 314 + " not available, check if controller is plugged in"); 315 } 316 return retVal; 317 } 318 319 /** 320 * Returns the number of axes on a given joystick port. 321 * 322 * @param stick The joystick port number 323 * @return The number of axes on the indicated joystick 324 */ 325 public int getStickAxisCount(int stick) { 326 if (stick < 0 || stick >= kJoystickPorts) { 327 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 328 } 329 synchronized (m_joystickMutex) { 330 return m_joystickAxes[stick].m_count; 331 } 332 } 333 334 /** 335 * Returns the number of POVs on a given joystick port. 336 * 337 * @param stick The joystick port number 338 * @return The number of POVs on the indicated joystick 339 */ 340 public int getStickPOVCount(int stick) { 341 if (stick < 0 || stick >= kJoystickPorts) { 342 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 343 } 344 synchronized (m_joystickMutex) { 345 return m_joystickPOVs[stick].m_count; 346 } 347 } 348 349 /** 350 * Gets the number of buttons on a joystick. 351 * 352 * @param stick The joystick port number 353 * @return The number of buttons on the indicated joystick 354 */ 355 public int getStickButtonCount(int stick) { 356 if (stick < 0 || stick >= kJoystickPorts) { 357 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 358 } 359 synchronized (m_joystickMutex) { 360 return m_joystickButtons[stick].m_count; 361 } 362 } 363 364 /** 365 * Gets the value of isXbox on a joystick. 366 * 367 * @param stick The joystick port number 368 * @return A boolean that returns the value of isXbox 369 */ 370 public boolean getJoystickIsXbox(int stick) { 371 if (stick < 0 || stick >= kJoystickPorts) { 372 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 373 } 374 boolean error = false; 375 boolean retVal = false; 376 synchronized (m_joystickMutex) { 377 // TODO: Remove this when calling for descriptor on empty stick no longer 378 // crashes 379 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 380 error = true; 381 retVal = false; 382 } else if (HAL.getJoystickIsXbox((byte) stick) == 1) { 383 retVal = true; 384 } 385 } 386 if (error) { 387 reportJoystickUnpluggedWarning("Joystick on port " + stick 388 + " not available, check if controller is plugged in"); 389 } 390 return retVal; 391 } 392 393 /** 394 * Gets the value of type on a joystick. 395 * 396 * @param stick The joystick port number 397 * @return The value of type 398 */ 399 public int getJoystickType(int stick) { 400 if (stick < 0 || stick >= kJoystickPorts) { 401 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 402 } 403 boolean error = false; 404 int retVal = -1; 405 synchronized (m_joystickMutex) { 406 // TODO: Remove this when calling for descriptor on empty stick no longer 407 // crashes 408 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 409 error = true; 410 retVal = -1; 411 } else { 412 retVal = HAL.getJoystickType((byte) stick); 413 } 414 } 415 if (error) { 416 reportJoystickUnpluggedWarning("Joystick on port " + stick 417 + " not available, check if controller is plugged in"); 418 } 419 return retVal; 420 } 421 422 /** 423 * Gets the name of the joystick at a port. 424 * 425 * @param stick The joystick port number 426 * @return The value of name 427 */ 428 public String getJoystickName(int stick) { 429 if (stick < 0 || stick >= kJoystickPorts) { 430 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 431 } 432 boolean error = false; 433 String retVal = ""; 434 synchronized (m_joystickMutex) { 435 // TODO: Remove this when calling for descriptor on empty stick no longer 436 // crashes 437 if (1 > m_joystickButtons[stick].m_count && 1 > m_joystickAxes[stick].m_count) { 438 error = true; 439 retVal = ""; 440 } else { 441 retVal = HAL.getJoystickName((byte) stick); 442 } 443 } 444 if (error) { 445 reportJoystickUnpluggedWarning("Joystick on port " + stick 446 + " not available, check if controller is plugged in"); 447 } 448 return retVal; 449 } 450 451 /** 452 * Returns the types of Axes on a given joystick port. 453 * 454 * @param stick The joystick port number 455 * @param axis The target axis 456 * @return What type of axis the axis is reporting to be 457 */ 458 public int getJoystickAxisType(int stick, int axis) { 459 if (stick < 0 || stick >= kJoystickPorts) { 460 throw new RuntimeException("Joystick index is out of range, should be 0-5"); 461 } 462 463 int retVal = -1; 464 synchronized (m_joystickMutex) { 465 retVal = HAL.getJoystickAxisType((byte) stick, (byte) axis); 466 } 467 return retVal; 468 } 469 470 /** 471 * Gets a value indicating whether the Driver Station requires the robot to be enabled. 472 * 473 * @return True if the robot is enabled, false otherwise. 474 */ 475 public boolean isEnabled() { 476 synchronized (m_controlWordMutex) { 477 updateControlWord(false); 478 return m_controlWordCache.getEnabled() && m_controlWordCache.getDSAttached(); 479 } 480 } 481 482 /** 483 * Gets a value indicating whether the Driver Station requires the robot to be disabled. 484 * 485 * @return True if the robot should be disabled, false otherwise. 486 */ 487 public boolean isDisabled() { 488 return !isEnabled(); 489 } 490 491 /** 492 * Gets a value indicating whether the Driver Station requires the robot to be running in 493 * autonomous mode. 494 * 495 * @return True if autonomous mode should be enabled, false otherwise. 496 */ 497 public boolean isAutonomous() { 498 synchronized (m_controlWordMutex) { 499 updateControlWord(false); 500 return m_controlWordCache.getAutonomous(); 501 } 502 } 503 504 /** 505 * Gets a value indicating whether the Driver Station requires the robot to be running in 506 * operator-controlled mode. 507 * 508 * @return True if operator-controlled mode should be enabled, false otherwise. 509 */ 510 public boolean isOperatorControl() { 511 return !(isAutonomous() || isTest()); 512 } 513 514 /** 515 * Gets a value indicating whether the Driver Station requires the robot to be running in test 516 * mode. 517 * 518 * @return True if test mode should be enabled, false otherwise. 519 */ 520 public boolean isTest() { 521 synchronized (m_controlWordMutex) { 522 updateControlWord(false); 523 return m_controlWordCache.getTest(); 524 } 525 } 526 527 /** 528 * Gets a value indicating whether the Driver Station is attached. 529 * 530 * @return True if Driver Station is attached, false otherwise. 531 */ 532 public boolean isDSAttached() { 533 synchronized (m_controlWordMutex) { 534 updateControlWord(false); 535 return m_controlWordCache.getDSAttached(); 536 } 537 } 538 539 /** 540 * Has a new control packet from the driver station arrived since the last time this function was 541 * called? 542 * 543 * @return True if the control data has been updated since the last call. 544 */ 545 public boolean isNewControlData() { 546 return m_newControlData.getAndSet(false); 547 } 548 549 @SuppressWarnings({"SummaryJavadoc", "JavadocMethod"}) 550 /** 551 * Is the driver station attached to a Field Management System? 552 * 553 * @return True if the robot is competing on a field being controlled by a Field Management System 554 */ 555 public boolean isFMSAttached() { 556 synchronized (m_controlWordMutex) { 557 updateControlWord(false); 558 return m_controlWordCache.getFMSAttached(); 559 } 560 } 561 562 /** 563 * Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled if 564 * the robot is disabled or e-stopped, the watdhog has expired, or if the roboRIO browns out. 565 * 566 * @return True if the FPGA outputs are enabled. 567 */ 568 public boolean isSysActive() { 569 return HAL.getSystemActive(); 570 } 571 572 /** 573 * Check if the system is browned out. 574 * 575 * @return True if the system is browned out 576 */ 577 public boolean isBrownedOut() { 578 return HAL.getBrownedOut(); 579 } 580 581 /** 582 * Get the current alliance from the FMS. 583 * 584 * @return the current alliance 585 */ 586 public Alliance getAlliance() { 587 AllianceStationID allianceStationID = HAL.getAllianceStation(); 588 if (allianceStationID == null) { 589 return Alliance.Invalid; 590 } 591 592 switch (allianceStationID) { 593 case Red1: 594 case Red2: 595 case Red3: 596 return Alliance.Red; 597 598 case Blue1: 599 case Blue2: 600 case Blue3: 601 return Alliance.Blue; 602 603 default: 604 return Alliance.Invalid; 605 } 606 } 607 608 /** 609 * Gets the location of the team's driver station controls. 610 * 611 * @return the location of the team's driver station controls: 1, 2, or 3 612 */ 613 public int getLocation() { 614 AllianceStationID allianceStationID = HAL.getAllianceStation(); 615 if (allianceStationID == null) { 616 return 0; 617 } 618 switch (allianceStationID) { 619 case Red1: 620 case Blue1: 621 return 1; 622 623 case Red2: 624 case Blue2: 625 return 2; 626 627 case Blue3: 628 case Red3: 629 return 3; 630 631 default: 632 return 0; 633 } 634 } 635 636 /** 637 * Wait for new data from the driver station. 638 */ 639 public void waitForData() { 640 waitForData(0); 641 } 642 643 /** 644 * Wait for new data or for timeout, which ever comes first. If timeout is 0, wait for new data 645 * only. 646 * 647 * @param timeout The maximum time in seconds to wait. 648 * @return true if there is new data, otherwise false 649 */ 650 public boolean waitForData(double timeout) { 651 long startTime = Utility.getFPGATime(); 652 long timeoutMicros = (long)(timeout * 1000000); 653 m_dataMutex.lock(); 654 try { 655 try { 656 while (!m_waitForDataPredicate) { 657 if (timeout > 0) { 658 long now = Utility.getFPGATime(); 659 if (now < startTime + timeoutMicros) { 660 // We still have time to wait 661 boolean signaled = m_dataCond.await(startTime + timeoutMicros - now, 662 TimeUnit.MICROSECONDS); 663 if (!signaled) { 664 // Return false if a timeout happened 665 return false; 666 } 667 } else { 668 // Time has elapsed. 669 return false; 670 } 671 } else { 672 m_dataCond.await(); 673 } 674 } 675 m_waitForDataPredicate = false; 676 // Return true if we have received a proper signal 677 return true; 678 } catch (InterruptedException ex) { 679 // return false on a thread interrupt 680 return false; 681 } 682 } finally { 683 m_dataMutex.unlock(); 684 } 685 } 686 687 /** 688 * Return the approximate match time The FMS does not send an official match time to the robots, 689 * but does send an approximate match time. The value will count down the time remaining in the 690 * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to 691 * dispute ref calls or guarantee that a function will trigger before the match ends) The 692 * Practice Match function of the DS approximates the behaviour seen on the field. 693 * 694 * @return Time remaining in current match period (auto or teleop) in seconds 695 */ 696 public double getMatchTime() { 697 return HAL.getMatchTime(); 698 } 699 700 /** 701 * Read the battery voltage. 702 * 703 * @return The battery voltage in Volts. 704 */ 705 public double getBatteryVoltage() { 706 return PowerJNI.getVinVoltage(); 707 } 708 709 /** 710 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 711 * purposes only. 712 * 713 * @param entering If true, starting disabled code; if false, leaving disabled code 714 */ 715 @SuppressWarnings("MethodName") 716 public void InDisabled(boolean entering) { 717 m_userInDisabled = entering; 718 } 719 720 /** 721 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 722 * purposes only. 723 * 724 * @param entering If true, starting autonomous code; if false, leaving autonomous code 725 */ 726 @SuppressWarnings("MethodName") 727 public void InAutonomous(boolean entering) { 728 m_userInAutonomous = entering; 729 } 730 731 /** 732 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 733 * purposes only. 734 * 735 * @param entering If true, starting teleop code; if false, leaving teleop code 736 */ 737 @SuppressWarnings("MethodName") 738 public void InOperatorControl(boolean entering) { 739 m_userInTeleop = entering; 740 } 741 742 /** 743 * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic 744 * purposes only. 745 * 746 * @param entering If true, starting test code; if false, leaving test code 747 */ 748 @SuppressWarnings("MethodName") 749 public void InTest(boolean entering) { 750 m_userInTest = entering; 751 } 752 753 /** 754 * Copy data from the DS task for the user. If no new data exists, it will just be returned, 755 * otherwise the data will be copied from the DS polling loop. 756 */ 757 protected void getData() { 758 // Get the status of all of the joysticks 759 for (byte stick = 0; stick < kJoystickPorts; stick++) { 760 m_joystickAxesCache[stick].m_count = 761 HAL.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes); 762 m_joystickPOVsCache[stick].m_count = 763 HAL.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs); 764 m_joystickButtonsCache[stick].m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer); 765 m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0); 766 } 767 // Force a control word update, to make sure the data is the newest. 768 updateControlWord(true); 769 770 // lock joystick mutex to swap cache data 771 synchronized (m_joystickMutex) { 772 // move cache to actual data 773 HALJoystickAxes[] currentAxes = m_joystickAxes; 774 m_joystickAxes = m_joystickAxesCache; 775 m_joystickAxesCache = currentAxes; 776 777 HALJoystickButtons[] currentButtons = m_joystickButtons; 778 m_joystickButtons = m_joystickButtonsCache; 779 m_joystickButtonsCache = currentButtons; 780 781 HALJoystickPOVs[] currentPOVs = m_joystickPOVs; 782 m_joystickPOVs = m_joystickPOVsCache; 783 m_joystickPOVsCache = currentPOVs; 784 } 785 } 786 787 /** 788 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 789 * the DS. 790 */ 791 private void reportJoystickUnpluggedError(String message) { 792 double currentTime = Timer.getFPGATimestamp(); 793 if (currentTime > m_nextMessageTime) { 794 reportError(message, false); 795 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 796 } 797 } 798 799 /** 800 * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm 801 * the DS. 802 */ 803 private void reportJoystickUnpluggedWarning(String message) { 804 double currentTime = Timer.getFPGATimestamp(); 805 if (currentTime > m_nextMessageTime) { 806 reportWarning(message, false); 807 m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL; 808 } 809 } 810 811 /** 812 * Provides the service routine for the DS polling m_thread. 813 */ 814 private void run() { 815 int safetyCounter = 0; 816 while (m_threadKeepAlive) { 817 HAL.waitForDSData(); 818 getData(); 819 m_dataMutex.lock(); 820 try { 821 m_waitForDataPredicate = true; 822 m_dataCond.signalAll(); 823 } finally { 824 m_dataMutex.unlock(); 825 } 826 // notify isNewControlData variable 827 m_newControlData.set(true); 828 829 if (++safetyCounter >= 4) { 830 MotorSafetyHelper.checkMotors(); 831 safetyCounter = 0; 832 } 833 if (m_userInDisabled) { 834 HAL.observeUserProgramDisabled(); 835 } 836 if (m_userInAutonomous) { 837 HAL.observeUserProgramAutonomous(); 838 } 839 if (m_userInTeleop) { 840 HAL.observeUserProgramTeleop(); 841 } 842 if (m_userInTest) { 843 HAL.observeUserProgramTest(); 844 } 845 } 846 } 847 848 /** 849 * Updates the data in the control word cache. Updates if the force parameter is set, or if 850 * 50ms have passed since the last update. 851 * 852 * @param force True to force an update to the cache, otherwise update if 50ms have passed. 853 */ 854 private void updateControlWord(boolean force) { 855 long now = System.currentTimeMillis(); 856 synchronized (m_controlWordMutex) { 857 if (now - m_lastControlWordUpdate > 50 || force) { 858 HAL.getControlWord(m_controlWordCache); 859 m_lastControlWordUpdate = now; 860 } 861 } 862 } 863}