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