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 org.wpilib.driverstation.internal;
006
007import java.util.HashMap;
008import java.util.Map;
009import java.util.Optional;
010import java.util.OptionalDouble;
011import java.util.OptionalInt;
012import java.util.concurrent.locks.ReentrantLock;
013import java.util.stream.Collectors;
014import org.wpilib.datalog.BooleanArrayLogEntry;
015import org.wpilib.datalog.DataLog;
016import org.wpilib.datalog.FloatArrayLogEntry;
017import org.wpilib.datalog.IntegerArrayLogEntry;
018import org.wpilib.datalog.StringLogEntry;
019import org.wpilib.datalog.StructLogEntry;
020import org.wpilib.driverstation.Alliance;
021import org.wpilib.driverstation.MatchType;
022import org.wpilib.driverstation.POVDirection;
023import org.wpilib.driverstation.TouchpadFinger;
024import org.wpilib.framework.OpModeRobot;
025import org.wpilib.framework.TimedRobot;
026import org.wpilib.hardware.hal.AllianceStationID;
027import org.wpilib.hardware.hal.ControlWord;
028import org.wpilib.hardware.hal.DriverStationJNI;
029import org.wpilib.hardware.hal.HAL;
030import org.wpilib.hardware.hal.MatchInfoData;
031import org.wpilib.hardware.hal.OpModeOption;
032import org.wpilib.hardware.hal.RobotMode;
033import org.wpilib.networktables.BooleanPublisher;
034import org.wpilib.networktables.IntegerPublisher;
035import org.wpilib.networktables.NetworkTableInstance;
036import org.wpilib.networktables.StringPublisher;
037import org.wpilib.networktables.StringTopic;
038import org.wpilib.networktables.StructPublisher;
039import org.wpilib.system.Timer;
040import org.wpilib.util.Color;
041import org.wpilib.util.WPIUtilJNI;
042import org.wpilib.util.concurrent.EventVector;
043
044/** Provide access to the network communication data to / from the Driver Station. */
045public final class DriverStationBackend {
046  /** Number of Joystick ports. */
047  public static final int JOYSTICK_PORTS = 6;
048
049  private static final long[] m_metadataCache = new long[7];
050  private static final float[] m_touchpadFingersCache = new float[8];
051
052  private static int availableToCount(long available) {
053    // Top bit has to be set
054    if (available < 0) {
055      return 64;
056    }
057
058    int count = 0;
059
060    // Top bit not set, we will eventually get a 0 bit
061    while ((available & 0x1) != 0) {
062      count++;
063      available >>= 1;
064    }
065    return count;
066  }
067
068  private static final class HALJoystickTouchpadFinger {
069    float m_x;
070    float m_y;
071    boolean m_down;
072  }
073
074  private static class HALJoystickTouchpad {
075    final HALJoystickTouchpadFinger[] m_fingers =
076        new HALJoystickTouchpadFinger[DriverStationJNI.MAX_JOYSTICK_TOUCHPAD_FINGERS];
077    int m_count;
078
079    HALJoystickTouchpad() {
080      for (int i = 0; i < m_fingers.length; i++) {
081        m_fingers[i] = new HALJoystickTouchpadFinger();
082      }
083    }
084  }
085
086  private static class HALJoystickTouchpads {
087    final HALJoystickTouchpad[] m_touchpads =
088        new HALJoystickTouchpad[DriverStationJNI.MAX_JOYSTICK_TOUCHPADS];
089    int m_count;
090
091    HALJoystickTouchpads() {
092      for (int i = 0; i < m_touchpads.length; i++) {
093        m_touchpads[i] = new HALJoystickTouchpad();
094      }
095    }
096  }
097
098  private static final class HALJoystickButtons {
099    long m_buttons;
100    long m_available;
101  }
102
103  private static class HALJoystickAxes {
104    final float[] m_axes;
105    int m_available;
106
107    HALJoystickAxes(int count) {
108      m_axes = new float[count];
109    }
110  }
111
112  private static class HALJoystickAxesRaw {
113    final short[] m_axes;
114
115    @SuppressWarnings("unused")
116    int m_available;
117
118    HALJoystickAxesRaw(int count) {
119      m_axes = new short[count];
120    }
121  }
122
123  private static class HALJoystickPOVs {
124    final byte[] m_povs;
125    int m_available;
126
127    HALJoystickPOVs(int count) {
128      m_povs = new byte[count];
129      for (int i = 0; i < count; i++) {
130        m_povs[i] = 0;
131      }
132    }
133  }
134
135  private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
136  private static double m_nextMessageTime;
137
138  private static String opModeToString(long id) {
139    if (id == 0) {
140      return "";
141    }
142    m_opModesMutex.lock();
143    try {
144      OpModeOption option = m_opModes.get(id);
145      if (option != null) {
146        return option.name;
147      }
148    } finally {
149      m_opModesMutex.unlock();
150    }
151    return "<" + id + ">";
152  }
153
154  private static class MatchDataSender {
155    private static final String kSmartDashboardType = "FMSInfo";
156
157    final StringPublisher gameData;
158    final StringPublisher eventName;
159    final IntegerPublisher matchNumber;
160    final IntegerPublisher replayNumber;
161    final IntegerPublisher matchType;
162    final BooleanPublisher alliance;
163    final IntegerPublisher station;
164    final StructPublisher<ControlWord> controlWord;
165    final StringPublisher opMode;
166    boolean oldIsRedAlliance = true;
167    int oldStationNumber = 1;
168    String oldEventName = "";
169    String oldGameData = "";
170    int oldMatchNumber;
171    int oldReplayNumber;
172    int oldMatchType;
173    final ControlWord oldControlWord = new ControlWord();
174    final ControlWord currentControlWord = new ControlWord();
175
176    MatchDataSender() {
177      var table = NetworkTableInstance.getDefault().getTable("FMSInfo");
178      table
179          .getStringTopic(".type")
180          .publishEx(
181              StringTopic.TYPE_STRING, "{\"SmartDashboard\":\"" + kSmartDashboardType + "\"}")
182          .set(kSmartDashboardType);
183      gameData = table.getStringTopic("GameData").publish();
184      gameData.set("");
185      eventName = table.getStringTopic("EventName").publish();
186      eventName.set("");
187      matchNumber = table.getIntegerTopic("MatchNumber").publish();
188      matchNumber.set(0);
189      replayNumber = table.getIntegerTopic("ReplayNumber").publish();
190      replayNumber.set(0);
191      matchType = table.getIntegerTopic("MatchType").publish();
192      matchType.set(0);
193      alliance = table.getBooleanTopic("IsRedAlliance").publish();
194      alliance.set(true);
195      station = table.getIntegerTopic("StationNumber").publish();
196      station.set(1);
197      controlWord = table.getStructTopic("ControlWord", ControlWord.struct).publish();
198      controlWord.set(oldControlWord);
199      opMode = table.getStringTopic("OpMode").publish();
200      opMode.set("");
201    }
202
203    @SuppressWarnings("VariableDeclarationUsageDistance")
204    private void sendMatchData() {
205      AllianceStationID allianceID = DriverStationJNI.getAllianceStation();
206      final int stationNumber =
207          switch (allianceID) {
208            case BLUE_1, RED_1 -> 1;
209            case BLUE_2, RED_2 -> 2;
210            case BLUE_3, RED_3, UNKNOWN -> 3;
211          };
212      final boolean isRedAlliance =
213          switch (allianceID) {
214            case BLUE_1, BLUE_2, BLUE_3 -> false;
215            case RED_1, RED_2, RED_3, UNKNOWN -> true;
216          };
217
218      String currentEventName;
219      String currentGameData;
220      int currentMatchNumber;
221      int currentReplayNumber;
222      int currentMatchType;
223      m_cacheDataMutex.lock();
224      try {
225        currentEventName = DriverStationBackend.m_matchInfo.eventName;
226        currentGameData = DriverStationBackend.m_gameData;
227        currentMatchNumber = DriverStationBackend.m_matchInfo.matchNumber;
228        currentReplayNumber = DriverStationBackend.m_matchInfo.replayNumber;
229        currentMatchType = DriverStationBackend.m_matchInfo.matchType;
230      } finally {
231        m_cacheDataMutex.unlock();
232      }
233      DriverStationJNI.getControlWord(currentControlWord);
234
235      if (oldIsRedAlliance != isRedAlliance) {
236        alliance.set(isRedAlliance);
237        oldIsRedAlliance = isRedAlliance;
238      }
239      if (oldStationNumber != stationNumber) {
240        station.set(stationNumber);
241        oldStationNumber = stationNumber;
242      }
243      if (!oldEventName.equals(currentEventName)) {
244        eventName.set(currentEventName);
245        oldEventName = currentEventName;
246      }
247      if (!oldGameData.equals(currentGameData)) {
248        gameData.set(currentGameData);
249        oldGameData = currentGameData;
250      }
251      if (currentMatchNumber != oldMatchNumber) {
252        matchNumber.set(currentMatchNumber);
253        oldMatchNumber = currentMatchNumber;
254      }
255      if (currentReplayNumber != oldReplayNumber) {
256        replayNumber.set(currentReplayNumber);
257        oldReplayNumber = currentReplayNumber;
258      }
259      if (currentMatchType != oldMatchType) {
260        matchType.set(currentMatchType);
261        oldMatchType = currentMatchType;
262      }
263      if (!currentControlWord.equals(oldControlWord)) {
264        long currentOpModeId = currentControlWord.getOpModeId();
265        if (currentOpModeId != oldControlWord.getOpModeId()) {
266          opMode.set(opModeToString(currentOpModeId));
267        }
268        controlWord.set(currentControlWord);
269        oldControlWord.update(currentControlWord);
270      }
271    }
272  }
273
274  private static class JoystickLogSender {
275    JoystickLogSender(DataLog log, int stick, long timestamp) {
276      m_stick = stick;
277
278      m_logButtons = new BooleanArrayLogEntry(log, "DS:joystick" + stick + "/buttons", timestamp);
279      m_logAxes = new FloatArrayLogEntry(log, "DS:joystick" + stick + "/axes", timestamp);
280      m_logPOVs = new IntegerArrayLogEntry(log, "DS:joystick" + stick + "/povs", timestamp);
281
282      appendButtons(m_joystickButtons[m_stick], timestamp);
283      appendAxes(m_joystickAxes[m_stick], timestamp);
284      appendPOVs(m_joystickPOVs[m_stick], timestamp);
285    }
286
287    public void send(long timestamp) {
288      HALJoystickButtons buttons = m_joystickButtons[m_stick];
289      if (buttons.m_available != m_prevButtons.m_available
290          || buttons.m_buttons != m_prevButtons.m_buttons) {
291        appendButtons(buttons, timestamp);
292      }
293
294      HALJoystickAxes axes = m_joystickAxes[m_stick];
295      int available = axes.m_available;
296      boolean needToLog = false;
297      if (available != m_prevAxes.m_available) {
298        needToLog = true;
299      } else {
300        for (int i = 0; i < m_prevAxes.m_axes.length; i++) {
301          if (axes.m_axes[i] != m_prevAxes.m_axes[i]) {
302            needToLog = true;
303            break;
304          }
305        }
306      }
307      if (needToLog) {
308        appendAxes(axes, timestamp);
309      }
310
311      HALJoystickPOVs povs = m_joystickPOVs[m_stick];
312      available = m_joystickPOVs[m_stick].m_available;
313      needToLog = false;
314      if (available != m_prevPOVs.m_available) {
315        needToLog = true;
316      } else {
317        for (int i = 0; i < m_prevPOVs.m_povs.length; i++) {
318          if (povs.m_povs[i] != m_prevPOVs.m_povs[i]) {
319            needToLog = true;
320            break;
321          }
322        }
323      }
324      if (needToLog) {
325        appendPOVs(povs, timestamp);
326      }
327    }
328
329    void appendButtons(HALJoystickButtons buttons, long timestamp) {
330      int count = availableToCount(buttons.m_available);
331      if (m_sizedButtons == null || m_sizedButtons.length != count) {
332        m_sizedButtons = new boolean[count];
333      }
334      long buttonsValue = buttons.m_buttons;
335      for (int i = 0; i < count; i++) {
336        m_sizedButtons[i] = (buttonsValue & (1L << i)) != 0;
337      }
338      m_logButtons.append(m_sizedButtons, timestamp);
339      m_prevButtons.m_available = buttons.m_available;
340      m_prevButtons.m_buttons = buttons.m_buttons;
341    }
342
343    void appendAxes(HALJoystickAxes axes, long timestamp) {
344      int count = availableToCount(axes.m_available);
345      if (m_sizedAxes == null || m_sizedAxes.length != count) {
346        m_sizedAxes = new float[count];
347      }
348      System.arraycopy(axes.m_axes, 0, m_sizedAxes, 0, count);
349      m_logAxes.append(m_sizedAxes, timestamp);
350      m_prevAxes.m_available = axes.m_available;
351      System.arraycopy(axes.m_axes, 0, m_prevAxes.m_axes, 0, count);
352    }
353
354    void appendPOVs(HALJoystickPOVs povs, long timestamp) {
355      int count = availableToCount(povs.m_available);
356      if (m_sizedPOVs == null || m_sizedPOVs.length != count) {
357        m_sizedPOVs = new long[count];
358      }
359      for (int i = 0; i < count; i++) {
360        m_sizedPOVs[i] = povs.m_povs[i];
361      }
362      m_logPOVs.append(m_sizedPOVs, timestamp);
363      m_prevPOVs.m_available = povs.m_available;
364      System.arraycopy(povs.m_povs, 0, m_prevPOVs.m_povs, 0, count);
365    }
366
367    final int m_stick;
368    boolean[] m_sizedButtons;
369    float[] m_sizedAxes;
370    long[] m_sizedPOVs;
371    final HALJoystickButtons m_prevButtons = new HALJoystickButtons();
372    final HALJoystickAxes m_prevAxes = new HALJoystickAxes(DriverStationJNI.MAX_JOYSTICK_AXES);
373    final HALJoystickPOVs m_prevPOVs = new HALJoystickPOVs(DriverStationJNI.MAX_JOYSTICK_POVS);
374    final BooleanArrayLogEntry m_logButtons;
375    final FloatArrayLogEntry m_logAxes;
376    final IntegerArrayLogEntry m_logPOVs;
377  }
378
379  private static class DataLogSender {
380    DataLogSender(DataLog log, boolean logJoysticks, long timestamp) {
381      m_logControlWord =
382          StructLogEntry.create(log, "DS:controlWord", ControlWord.struct, timestamp);
383
384      // append initial control word value
385      m_logControlWord.append(m_controlWordCache, timestamp);
386      m_oldControlWord.update(m_controlWordCache);
387
388      // append initial opmode value
389      m_logOpMode = new StringLogEntry(log, "DS:opMode", timestamp);
390      m_logOpMode.append(m_opModeCache, timestamp);
391
392      if (logJoysticks) {
393        m_joysticks = new JoystickLogSender[JOYSTICK_PORTS];
394        for (int i = 0; i < JOYSTICK_PORTS; i++) {
395          m_joysticks[i] = new JoystickLogSender(log, i, timestamp);
396        }
397      } else {
398        m_joysticks = new JoystickLogSender[0];
399      }
400    }
401
402    public void send(long timestamp) {
403      // append control word value changes
404      if (!m_controlWordCache.equals(m_oldControlWord)) {
405        // append opmode value changes
406        long opModeId = m_controlWordCache.getOpModeId();
407        if (opModeId != m_oldControlWord.getOpModeId()) {
408          m_logOpMode.append(m_opModeCache, timestamp);
409        }
410
411        m_logControlWord.append(m_controlWordCache, timestamp);
412        m_oldControlWord.update(m_controlWordCache);
413      }
414
415      // append joystick value changes
416      for (JoystickLogSender joystick : m_joysticks) {
417        joystick.send(timestamp);
418      }
419    }
420
421    final ControlWord m_oldControlWord = new ControlWord();
422    final StructLogEntry<ControlWord> m_logControlWord;
423    final StringLogEntry m_logOpMode;
424
425    final JoystickLogSender[] m_joysticks;
426  }
427
428  // Joystick User Data
429  private static HALJoystickAxes[] m_joystickAxes = new HALJoystickAxes[JOYSTICK_PORTS];
430  private static HALJoystickAxesRaw[] m_joystickAxesRaw = new HALJoystickAxesRaw[JOYSTICK_PORTS];
431  private static HALJoystickPOVs[] m_joystickPOVs = new HALJoystickPOVs[JOYSTICK_PORTS];
432  private static HALJoystickButtons[] m_joystickButtons = new HALJoystickButtons[JOYSTICK_PORTS];
433  private static HALJoystickTouchpads[] m_joystickTouchpads =
434      new HALJoystickTouchpads[JOYSTICK_PORTS];
435  private static MatchInfoData m_matchInfo = new MatchInfoData();
436  private static String m_gameData = "";
437  private static ControlWord m_controlWord = new ControlWord();
438  private static String m_opMode = "";
439  private static EventVector m_refreshEvents = new EventVector();
440
441  // Joystick Cached Data
442  private static HALJoystickAxes[] m_joystickAxesCache = new HALJoystickAxes[JOYSTICK_PORTS];
443  private static HALJoystickAxesRaw[] m_joystickAxesRawCache =
444      new HALJoystickAxesRaw[JOYSTICK_PORTS];
445  private static HALJoystickPOVs[] m_joystickPOVsCache = new HALJoystickPOVs[JOYSTICK_PORTS];
446  private static HALJoystickButtons[] m_joystickButtonsCache =
447      new HALJoystickButtons[JOYSTICK_PORTS];
448  private static HALJoystickTouchpads[] m_joystickTouchpadsCache =
449      new HALJoystickTouchpads[JOYSTICK_PORTS];
450  private static MatchInfoData m_matchInfoCache = new MatchInfoData();
451  private static String m_gameDataCache = "";
452  private static ControlWord m_controlWordCache = new ControlWord();
453
454  private static String m_opModeCache = "";
455
456  // Joystick button rising/falling edge flags
457  private static long[] m_joystickButtonsPressed = new long[JOYSTICK_PORTS];
458  private static long[] m_joystickButtonsReleased = new long[JOYSTICK_PORTS];
459
460  private static final MatchDataSender m_matchDataSender;
461  private static DataLogSender m_dataLogSender;
462
463  private static final ReentrantLock m_cacheDataMutex = new ReentrantLock();
464
465  private static boolean m_silenceJoystickWarning;
466
467  private static boolean m_userProgramStarted = false;
468  private static final Map<Long, OpModeOption> m_opModes = new HashMap<>();
469  private static final ReentrantLock m_opModesMutex = new ReentrantLock();
470
471  /**
472   * DriverStation constructor.
473   *
474   * <p>The single DriverStation instance is created statically with the instance static member
475   * variable.
476   */
477  private DriverStationBackend() {}
478
479  static {
480    HAL.initialize(500, 0);
481
482    for (int i = 0; i < JOYSTICK_PORTS; i++) {
483      m_joystickButtons[i] = new HALJoystickButtons();
484      m_joystickAxes[i] = new HALJoystickAxes(DriverStationJNI.MAX_JOYSTICK_AXES);
485      m_joystickAxesRaw[i] = new HALJoystickAxesRaw(DriverStationJNI.MAX_JOYSTICK_AXES);
486      m_joystickPOVs[i] = new HALJoystickPOVs(DriverStationJNI.MAX_JOYSTICK_POVS);
487      m_joystickTouchpads[i] = new HALJoystickTouchpads();
488
489      m_joystickButtonsCache[i] = new HALJoystickButtons();
490      m_joystickAxesCache[i] = new HALJoystickAxes(DriverStationJNI.MAX_JOYSTICK_AXES);
491      m_joystickAxesRawCache[i] = new HALJoystickAxesRaw(DriverStationJNI.MAX_JOYSTICK_AXES);
492      m_joystickPOVsCache[i] = new HALJoystickPOVs(DriverStationJNI.MAX_JOYSTICK_POVS);
493      m_joystickTouchpadsCache[i] = new HALJoystickTouchpads();
494    }
495
496    m_matchDataSender = new MatchDataSender();
497  }
498
499  /**
500   * Report error to Driver Station. Optionally appends Stack trace to error message.
501   *
502   * @param error The error to report.
503   * @param printTrace If true, append stack trace to error string
504   */
505  public static void reportError(String error, boolean printTrace) {
506    reportErrorImpl(true, 1, error, printTrace);
507  }
508
509  /**
510   * Report error to Driver Station. Appends provided stack trace to error message.
511   *
512   * @param error The error to report.
513   * @param stackTrace The stack trace to append
514   */
515  public static void reportError(String error, StackTraceElement[] stackTrace) {
516    reportErrorImpl(true, 1, error, stackTrace);
517  }
518
519  /**
520   * Report warning to Driver Station. Optionally appends Stack trace to warning message.
521   *
522   * @param warning The warning to report.
523   * @param printTrace If true, append stack trace to warning string
524   */
525  public static void reportWarning(String warning, boolean printTrace) {
526    reportErrorImpl(false, 1, warning, printTrace);
527  }
528
529  /**
530   * Report warning to Driver Station. Appends provided stack trace to warning message.
531   *
532   * @param warning The warning to report.
533   * @param stackTrace The stack trace to append
534   */
535  public static void reportWarning(String warning, StackTraceElement[] stackTrace) {
536    reportErrorImpl(false, 1, warning, stackTrace);
537  }
538
539  private static void reportErrorImpl(boolean isError, int code, String error, boolean printTrace) {
540    reportErrorImpl(isError, code, error, printTrace, Thread.currentThread().getStackTrace(), 3);
541  }
542
543  private static void reportErrorImpl(
544      boolean isError, int code, String error, StackTraceElement[] stackTrace) {
545    reportErrorImpl(isError, code, error, true, stackTrace, 0);
546  }
547
548  private static void reportErrorImpl(
549      boolean isError,
550      int code,
551      String error,
552      boolean printTrace,
553      StackTraceElement[] stackTrace,
554      int stackTraceFirst) {
555    String locString;
556    if (stackTrace.length >= stackTraceFirst + 1) {
557      locString = stackTrace[stackTraceFirst].toString();
558    } else {
559      locString = "";
560    }
561    StringBuilder traceString = new StringBuilder();
562    if (printTrace) {
563      boolean haveLoc = false;
564      for (int i = stackTraceFirst; i < stackTrace.length; i++) {
565        String loc = stackTrace[i].toString();
566        traceString.append("\tat ").append(loc).append('\n');
567        // get first user function
568        if (!haveLoc && !loc.startsWith("org.wpilib")) {
569          locString = loc;
570          haveLoc = true;
571        }
572      }
573    }
574    DriverStationJNI.sendError(
575        isError, code, false, error, locString, traceString.toString(), true);
576  }
577
578  /**
579   * The state of one joystick button.
580   *
581   * @param stick The joystick to read.
582   * @param button The button index.
583   * @return The state of the joystick button.
584   */
585  public static boolean getStickButton(final int stick, final int button) {
586    if (stick < 0 || stick >= JOYSTICK_PORTS) {
587      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
588    }
589    if (button < 0 || button >= DriverStationJNI.MAX_JOYSTICK_BUTTONS) {
590      throw new IllegalArgumentException("Joystick Button is out of range");
591    }
592
593    long mask = 1L << button;
594
595    m_cacheDataMutex.lock();
596    try {
597      if ((m_joystickButtons[stick].m_available & mask) != 0) {
598        return (m_joystickButtons[stick].m_buttons & mask) != 0;
599      }
600    } finally {
601      m_cacheDataMutex.unlock();
602    }
603
604    reportJoystickWarning(
605        stick, "Joystick Button " + button + " on port " + stick + " not available");
606    return false;
607  }
608
609  /**
610   * The state of one joystick button if available.
611   *
612   * @param stick The joystick to read.
613   * @param button The button index.
614   * @return The state of the joystick button, or false if the button is not available.
615   */
616  public static Optional<Boolean> getStickButtonIfAvailable(final int stick, final int button) {
617    if (stick < 0 || stick >= JOYSTICK_PORTS) {
618      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
619    }
620    if (button < 0 || button >= DriverStationJNI.MAX_JOYSTICK_BUTTONS) {
621      throw new IllegalArgumentException("Joystick Button is out of range");
622    }
623
624    long mask = 1L << button;
625
626    m_cacheDataMutex.lock();
627    try {
628      if ((m_joystickButtons[stick].m_available & mask) != 0) {
629        return Optional.of((m_joystickButtons[stick].m_buttons & mask) != 0);
630      }
631    } finally {
632      m_cacheDataMutex.unlock();
633    }
634    return Optional.empty();
635  }
636
637  /**
638   * Whether one joystick button was pressed since the last check.
639   *
640   * @param stick The joystick to read.
641   * @param button The button index.
642   * @return Whether the joystick button was pressed since the last check.
643   */
644  public static boolean getStickButtonPressed(final int stick, final int button) {
645    if (stick < 0 || stick >= JOYSTICK_PORTS) {
646      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
647    }
648    if (button < 0 || button >= DriverStationJNI.MAX_JOYSTICK_BUTTONS) {
649      throw new IllegalArgumentException("Joystick Button is out of range");
650    }
651
652    long mask = 1L << button;
653
654    m_cacheDataMutex.lock();
655    try {
656      if ((m_joystickButtons[stick].m_available & mask) != 0) {
657        // If button was pressed, clear flag and return true
658        if ((m_joystickButtonsPressed[stick] & mask) != 0) {
659          m_joystickButtonsPressed[stick] &= ~mask;
660          return true;
661        } else {
662          return false;
663        }
664      }
665    } finally {
666      m_cacheDataMutex.unlock();
667    }
668
669    reportJoystickWarning(
670        stick, "Joystick Button " + button + " on port " + stick + " not available");
671    return false;
672  }
673
674  /**
675   * Whether one joystick button was released since the last check.
676   *
677   * @param stick The joystick to read.
678   * @param button The button index, beginning at 0.
679   * @return Whether the joystick button was released since the last check.
680   */
681  public static boolean getStickButtonReleased(final int stick, final int button) {
682    if (stick < 0 || stick >= JOYSTICK_PORTS) {
683      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
684    }
685    if (button < 0 || button >= DriverStationJNI.MAX_JOYSTICK_BUTTONS) {
686      throw new IllegalArgumentException("Joystick Button is out of range");
687    }
688
689    long mask = 1L << button;
690
691    m_cacheDataMutex.lock();
692    try {
693      if ((m_joystickButtons[stick].m_available & mask) != 0) {
694        // If button was released, clear flag and return true
695        if ((m_joystickButtonsReleased[stick] & mask) != 0) {
696          m_joystickButtonsReleased[stick] &= ~mask;
697          return true;
698        } else {
699          return false;
700        }
701      }
702    } finally {
703      m_cacheDataMutex.unlock();
704    }
705
706    reportJoystickWarning(
707        stick, "Joystick Button " + button + " on port " + stick + " not available");
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 >= JOYSTICK_PORTS) {
721      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
722    }
723    if (axis < 0 || axis >= DriverStationJNI.MAX_JOYSTICK_AXES) {
724      throw new IllegalArgumentException("Joystick axis is out of range");
725    }
726
727    int mask = 1 << axis;
728
729    m_cacheDataMutex.lock();
730    try {
731      if ((m_joystickAxes[stick].m_available & mask) != 0) {
732        return m_joystickAxes[stick].m_axes[axis];
733      }
734    } finally {
735      m_cacheDataMutex.unlock();
736    }
737
738    reportJoystickWarning(stick, "Joystick axis " + axis + " on port " + stick + " not available");
739    return 0.0;
740  }
741
742  /**
743   * Get the state of a touchpad finger on the joystick.
744   *
745   * @param stick The joystick to read.
746   * @param touchpad The touchpad to read.
747   * @param finger The finger to read.
748   * @return the state of the touchpad finger.
749   */
750  public static TouchpadFinger getStickTouchpadFinger(int stick, int touchpad, int finger) {
751    if (stick < 0 || stick >= JOYSTICK_PORTS) {
752      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
753    }
754    if (touchpad < 0 || touchpad >= DriverStationJNI.MAX_JOYSTICK_TOUCHPADS) {
755      throw new IllegalArgumentException("Joystick touchpad is out of range");
756    }
757    if (finger < 0 || finger >= DriverStationJNI.MAX_JOYSTICK_TOUCHPAD_FINGERS) {
758      throw new IllegalArgumentException("Joystick touchpad finger is out of range");
759    }
760
761    int touchpadCount;
762    m_cacheDataMutex.lock();
763    try {
764      touchpadCount = m_joystickTouchpads[stick].m_count;
765      if (touchpad < touchpadCount) {
766        HALJoystickTouchpad tp = m_joystickTouchpads[stick].m_touchpads[touchpad];
767        if (finger < tp.m_count) {
768          return new TouchpadFinger(
769              tp.m_fingers[finger].m_down, tp.m_fingers[finger].m_x, tp.m_fingers[finger].m_y);
770        }
771      }
772    } finally {
773      m_cacheDataMutex.unlock();
774    }
775
776    reportJoystickWarning(
777        stick,
778        "Joystick touchpad finger "
779            + finger
780            + " on touchpad "
781            + touchpad
782            + " on port "
783            + stick
784            + " not available");
785    return new TouchpadFinger(false, 0.0f, 0.0f);
786  }
787
788  /**
789   * Get whether a touchpad finger on the joystick is available.
790   *
791   * @param stick The joystick to read.
792   * @param touchpad The touchpad to read.
793   * @param finger The finger to read.
794   * @return whether the touchpad finger is available.
795   */
796  public static boolean getStickTouchpadFingerAvailable(int stick, int touchpad, int finger) {
797    if (stick < 0 || stick >= JOYSTICK_PORTS) {
798      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
799    }
800    if (touchpad < 0 || touchpad >= DriverStationJNI.MAX_JOYSTICK_TOUCHPADS) {
801      throw new IllegalArgumentException("Joystick touchpad is out of range");
802    }
803    if (finger < 0 || finger >= DriverStationJNI.MAX_JOYSTICK_TOUCHPAD_FINGERS) {
804      throw new IllegalArgumentException("Joystick touchpad finger is out of range");
805    }
806
807    int touchpadCount;
808    m_cacheDataMutex.lock();
809    try {
810      touchpadCount = m_joystickTouchpads[stick].m_count;
811      if (touchpad < touchpadCount) {
812        HALJoystickTouchpad tp = m_joystickTouchpads[stick].m_touchpads[touchpad];
813        if (finger < tp.m_count) {
814          return true;
815        }
816      }
817    } finally {
818      m_cacheDataMutex.unlock();
819    }
820
821    return false;
822  }
823
824  /**
825   * Get the value of the axis on a joystick if available. This depends on the mapping of the
826   * joystick connected to the specified port.
827   *
828   * @param stick The joystick to read.
829   * @param axis The analog axis value to read from the joystick.
830   * @return The value of the axis on the joystick, or 0 if the axis is not available.
831   */
832  public static OptionalDouble getStickAxisIfAvailable(int stick, int axis) {
833    if (stick < 0 || stick >= JOYSTICK_PORTS) {
834      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
835    }
836    if (axis < 0 || axis >= DriverStationJNI.MAX_JOYSTICK_AXES) {
837      throw new IllegalArgumentException("Joystick axis is out of range");
838    }
839
840    int mask = 1 << axis;
841
842    m_cacheDataMutex.lock();
843    try {
844      if ((m_joystickAxes[stick].m_available & mask) != 0) {
845        return OptionalDouble.of(m_joystickAxes[stick].m_axes[axis]);
846      }
847    } finally {
848      m_cacheDataMutex.unlock();
849    }
850
851    return OptionalDouble.empty();
852  }
853
854  /**
855   * Get the state of a POV on the joystick.
856   *
857   * @param stick The joystick to read.
858   * @param pov The POV to read.
859   * @return the angle of the POV.
860   */
861  public static POVDirection getStickPOV(int stick, int pov) {
862    if (stick < 0 || stick >= JOYSTICK_PORTS) {
863      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
864    }
865    if (pov < 0 || pov >= DriverStationJNI.MAX_JOYSTICK_POVS) {
866      throw new IllegalArgumentException("Joystick POV is out of range");
867    }
868
869    int mask = 1 << pov;
870
871    m_cacheDataMutex.lock();
872    try {
873      if ((m_joystickPOVs[stick].m_available & mask) != 0) {
874        return POVDirection.of(m_joystickPOVs[stick].m_povs[pov]);
875      }
876    } finally {
877      m_cacheDataMutex.unlock();
878    }
879
880    reportJoystickWarning(stick, "Joystick POV " + pov + " on port " + stick + " not available");
881    return POVDirection.CENTER;
882  }
883
884  /**
885   * The state of the buttons on the joystick.
886   *
887   * @param stick The joystick to read.
888   * @return The state of the buttons on the joystick.
889   */
890  public static long getStickButtons(final int stick) {
891    if (stick < 0 || stick >= JOYSTICK_PORTS) {
892      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
893    }
894
895    m_cacheDataMutex.lock();
896    try {
897      return m_joystickButtons[stick].m_buttons;
898    } finally {
899      m_cacheDataMutex.unlock();
900    }
901  }
902
903  /**
904   * Gets the maximum index of axes on a given joystick port.
905   *
906   * @param stick The joystick port number
907   * @return The maximum index of axes on the indicated joystick
908   */
909  public static int getStickAxesMaximumIndex(int stick) {
910    return availableToCount(getStickAxesAvailable(stick));
911  }
912
913  /**
914   * Returns the available bitmask of axes on a given joystick port.
915   *
916   * @param stick The joystick port number
917   * @return The number of axes available on the indicated joystick
918   */
919  public static int getStickAxesAvailable(int stick) {
920    if (stick < 0 || stick >= JOYSTICK_PORTS) {
921      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
922    }
923
924    m_cacheDataMutex.lock();
925    try {
926      return m_joystickAxes[stick].m_available;
927    } finally {
928      m_cacheDataMutex.unlock();
929    }
930  }
931
932  /**
933   * Gets the maximum index of povs on a given joystick port.
934   *
935   * @param stick The joystick port number
936   * @return The maximum index of povs on the indicated joystick
937   */
938  public static int getStickPOVsMaximumIndex(int stick) {
939    return availableToCount(getStickPOVsAvailable(stick));
940  }
941
942  /**
943   * Returns the available bitmask of povs on a given joystick port.
944   *
945   * @param stick The joystick port number
946   * @return The number of povs available on the indicated joystick
947   */
948  public static int getStickPOVsAvailable(int stick) {
949    if (stick < 0 || stick >= JOYSTICK_PORTS) {
950      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
951    }
952
953    m_cacheDataMutex.lock();
954    try {
955      return m_joystickPOVs[stick].m_available;
956    } finally {
957      m_cacheDataMutex.unlock();
958    }
959  }
960
961  /**
962   * Gets the maximum index of buttons on a given joystick port.
963   *
964   * @param stick The joystick port number
965   * @return The maximum index of buttons on the indicated joystick
966   */
967  public static int getStickButtonsMaximumIndex(int stick) {
968    return availableToCount(getStickButtonsAvailable(stick));
969  }
970
971  /**
972   * Gets the bitmask of buttons available.
973   *
974   * @param stick The joystick port number
975   * @return The buttons available on the indicated joystick
976   */
977  public static long getStickButtonsAvailable(int stick) {
978    if (stick < 0 || stick >= JOYSTICK_PORTS) {
979      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
980    }
981
982    m_cacheDataMutex.lock();
983    try {
984      return m_joystickButtons[stick].m_available;
985    } finally {
986      m_cacheDataMutex.unlock();
987    }
988  }
989
990  /**
991   * Gets the value of isGamepad on a joystick.
992   *
993   * @param stick The joystick port number
994   * @return A boolean that returns the value of isGamepad
995   */
996  public static boolean getJoystickIsGamepad(int stick) {
997    if (stick < 0 || stick >= JOYSTICK_PORTS) {
998      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
999    }
1000
1001    return DriverStationJNI.getJoystickIsGamepad((byte) stick) == 1;
1002  }
1003
1004  /**
1005   * Gets the value of type on a gamepad.
1006   *
1007   * @param stick The joystick port number
1008   * @return The value of type
1009   */
1010  public static int getJoystickGamepadType(int stick) {
1011    if (stick < 0 || stick >= JOYSTICK_PORTS) {
1012      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
1013    }
1014
1015    return DriverStationJNI.getJoystickGamepadType((byte) stick);
1016  }
1017
1018  /**
1019   * Gets the value of supported outputs on a joystick.
1020   *
1021   * @param stick The joystick port number
1022   * @return The value of supported outputs
1023   */
1024  public static int getJoystickSupportedOutputs(int stick) {
1025    if (stick < 0 || stick >= JOYSTICK_PORTS) {
1026      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
1027    }
1028
1029    return DriverStationJNI.getJoystickSupportedOutputs((byte) stick);
1030  }
1031
1032  /**
1033   * Gets the name of the joystick at a port.
1034   *
1035   * @param stick The joystick port number
1036   * @return The value of name
1037   */
1038  public static String getJoystickName(int stick) {
1039    if (stick < 0 || stick >= JOYSTICK_PORTS) {
1040      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
1041    }
1042
1043    return DriverStationJNI.getJoystickName((byte) stick);
1044  }
1045
1046  /**
1047   * Returns if a joystick is connected to the Driver Station.
1048   *
1049   * <p>This makes a best effort guess by looking at the reported number of axis, buttons, and POVs
1050   * attached.
1051   *
1052   * @param stick The joystick port number
1053   * @return true if a joystick is connected
1054   */
1055  public static boolean isJoystickConnected(int stick) {
1056    return getStickAxesAvailable(stick) != 0
1057        || getStickButtonsAvailable(stick) != 0
1058        || getStickPOVsAvailable(stick) != 0;
1059  }
1060
1061  /**
1062   * Gets a value indicating whether the Driver Station requires the robot to be enabled.
1063   *
1064   * @return True if the robot is enabled, false otherwise.
1065   */
1066  public static boolean isEnabled() {
1067    m_cacheDataMutex.lock();
1068    try {
1069      return m_controlWord.isEnabled() && m_controlWord.isDSAttached();
1070    } finally {
1071      m_cacheDataMutex.unlock();
1072    }
1073  }
1074
1075  /**
1076   * Gets a value indicating whether the Driver Station requires the robot to be disabled.
1077   *
1078   * @return True if the robot should be disabled, false otherwise.
1079   */
1080  public static boolean isDisabled() {
1081    return !isEnabled();
1082  }
1083
1084  /**
1085   * Gets a value indicating whether the Robot is e-stopped.
1086   *
1087   * @return True if the robot is e-stopped, false otherwise.
1088   */
1089  public static boolean isEStopped() {
1090    m_cacheDataMutex.lock();
1091    try {
1092      return m_controlWord.isEStopped();
1093    } finally {
1094      m_cacheDataMutex.unlock();
1095    }
1096  }
1097
1098  /**
1099   * Gets the current robot mode.
1100   *
1101   * <p>Note that this does not indicate whether the robot is enabled or disabled.
1102   *
1103   * @return robot mode
1104   */
1105  public static RobotMode getRobotMode() {
1106    m_cacheDataMutex.lock();
1107    try {
1108      return m_controlWord.getRobotMode();
1109    } finally {
1110      m_cacheDataMutex.unlock();
1111    }
1112  }
1113
1114  /**
1115   * Gets a value indicating whether the Driver Station requires the robot to be running in
1116   * autonomous mode.
1117   *
1118   * @return True if autonomous mode should be enabled, false otherwise.
1119   */
1120  public static boolean isAutonomous() {
1121    m_cacheDataMutex.lock();
1122    try {
1123      return m_controlWord.isAutonomous();
1124    } finally {
1125      m_cacheDataMutex.unlock();
1126    }
1127  }
1128
1129  /**
1130   * Gets a value indicating whether the Driver Station requires the robot to be running in
1131   * autonomous mode and enabled.
1132   *
1133   * @return True if autonomous should be set and the robot should be enabled.
1134   */
1135  public static boolean isAutonomousEnabled() {
1136    m_cacheDataMutex.lock();
1137    try {
1138      return m_controlWord.isAutonomousEnabled();
1139    } finally {
1140      m_cacheDataMutex.unlock();
1141    }
1142  }
1143
1144  /**
1145   * Gets a value indicating whether the Driver Station requires the robot to be running in
1146   * operator-controlled mode.
1147   *
1148   * @return True if operator-controlled mode should be enabled, false otherwise.
1149   */
1150  public static boolean isTeleop() {
1151    return m_controlWord.isTeleop();
1152  }
1153
1154  /**
1155   * Gets a value indicating whether the Driver Station requires the robot to be running in
1156   * operator-controller mode and enabled.
1157   *
1158   * @return True if operator-controlled mode should be set and the robot should be enabled.
1159   */
1160  public static boolean isTeleopEnabled() {
1161    m_cacheDataMutex.lock();
1162    try {
1163      return m_controlWord.isTeleopEnabled();
1164    } finally {
1165      m_cacheDataMutex.unlock();
1166    }
1167  }
1168
1169  /**
1170   * Gets a value indicating whether the Driver Station requires the robot to be running in Utility
1171   * mode.
1172   *
1173   * @return True if utility mode should be enabled, false otherwise.
1174   */
1175  public static boolean isUtility() {
1176    m_cacheDataMutex.lock();
1177    try {
1178      return m_controlWord.isUtility();
1179    } finally {
1180      m_cacheDataMutex.unlock();
1181    }
1182  }
1183
1184  /**
1185   * Gets a value indicating whether the Driver Station requires the robot to be running in Utility
1186   * mode and enabled.
1187   *
1188   * @return True if utility mode should be set and the robot should be enabled.
1189   */
1190  public static boolean isUtilityEnabled() {
1191    m_cacheDataMutex.lock();
1192    try {
1193      return m_controlWord.isUtilityEnabled();
1194    } finally {
1195      m_cacheDataMutex.unlock();
1196    }
1197  }
1198
1199  private static int convertColorToInt(Color color) {
1200    if (color == null) {
1201      return -1;
1202    }
1203    return (((int) (color.red * 255) & 0xff) << 16)
1204        | (((int) (color.green * 255) & 0xff) << 8)
1205        | ((int) (color.blue * 255) & 0xff);
1206  }
1207
1208  /**
1209   * Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
1210   * visible to the driver station.
1211   *
1212   * @param mode robot mode
1213   * @param name name of the operating mode
1214   * @param group group of the operating mode
1215   * @param description description of the operating mode
1216   * @param textColor text color, or null for default
1217   * @param backgroundColor background color, or null for default
1218   * @return unique ID used to later identify the operating mode
1219   * @throws IllegalArgumentException if name is empty or an operating mode with the same robot mode
1220   *     and name already exists
1221   */
1222  @SuppressWarnings("PMD.UseStringBufferForStringAppends")
1223  public static long addOpMode(
1224      RobotMode mode,
1225      String name,
1226      String group,
1227      String description,
1228      Color textColor,
1229      Color backgroundColor) {
1230    if (name.isBlank()) {
1231      throw new IllegalArgumentException("OpMode name must be non-blank");
1232    }
1233    // find unique ID
1234    m_opModesMutex.lock();
1235    try {
1236      String nameCopy = name;
1237      for (; ; ) {
1238        long id = OpModeOption.makeId(mode, nameCopy.hashCode());
1239        OpModeOption existing = m_opModes.get(id);
1240        if (existing == null) {
1241          m_opModes.put(
1242              id,
1243              new OpModeOption(
1244                  id,
1245                  name,
1246                  group,
1247                  description,
1248                  convertColorToInt(textColor),
1249                  convertColorToInt(backgroundColor)));
1250          return id;
1251        }
1252        if (existing.getMode() == mode && existing.name.equals(name)) {
1253          // already exists
1254          throw new IllegalArgumentException("OpMode " + name + " already exists for mode " + mode);
1255        }
1256        // collision, try again with space appended
1257        nameCopy += ' ';
1258      }
1259    } finally {
1260      m_opModesMutex.unlock();
1261    }
1262  }
1263
1264  /**
1265   * Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
1266   * visible to the driver station.
1267   *
1268   * @param mode robot mode
1269   * @param name name of the operating mode
1270   * @param group group of the operating mode
1271   * @param description description of the operating mode
1272   * @return unique ID used to later identify the operating mode
1273   * @throws IllegalArgumentException if name is empty or an operating mode with the same name
1274   *     already exists
1275   */
1276  public static long addOpMode(RobotMode mode, String name, String group, String description) {
1277    return addOpMode(mode, name, group, description, null, null);
1278  }
1279
1280  /**
1281   * Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
1282   * visible to the driver station.
1283   *
1284   * @param mode robot mode
1285   * @param name name of the operating mode
1286   * @param group group of the operating mode
1287   * @return unique ID used to later identify the operating mode
1288   * @throws IllegalArgumentException if name is empty or an operating mode with the same name
1289   *     already exists
1290   */
1291  public static long addOpMode(RobotMode mode, String name, String group) {
1292    return addOpMode(mode, name, group, "");
1293  }
1294
1295  /**
1296   * Adds an operating mode option. It's necessary to call publishOpModes() to make the added modes
1297   * visible to the driver station.
1298   *
1299   * @param mode robot mode
1300   * @param name name of the operating mode
1301   * @return unique ID used to later identify the operating mode
1302   * @throws IllegalArgumentException if name is empty or an operating mode with the same name
1303   *     already exists
1304   */
1305  public static long addOpMode(RobotMode mode, String name) {
1306    return addOpMode(mode, name, "");
1307  }
1308
1309  /**
1310   * Removes an operating mode option. It's necessary to call publishOpModes() to make the removed
1311   * mode no longer visible to the driver station.
1312   *
1313   * @param mode robot mode
1314   * @param name name of the operating mode
1315   * @return unique ID for the opmode, or 0 if not found
1316   */
1317  public static long removeOpMode(RobotMode mode, String name) {
1318    if (name.isBlank()) {
1319      return 0;
1320    }
1321    m_opModesMutex.lock();
1322    try {
1323      // we have to loop over all entries to find the one with the correct name
1324      // because the of the unique ID generation scheme
1325      for (OpModeOption opMode : m_opModes.values()) {
1326        if (opMode.getMode() == mode && opMode.name.equals(name)) {
1327          m_opModes.remove(opMode.id);
1328          return opMode.id;
1329        }
1330      }
1331    } finally {
1332      m_opModesMutex.unlock();
1333    }
1334    return 0;
1335  }
1336
1337  /** Publishes the operating mode options to the driver station. */
1338  public static void publishOpModes() {
1339    m_opModesMutex.lock();
1340    try {
1341      OpModeOption[] options = new OpModeOption[m_opModes.size()];
1342      DriverStationJNI.setOpModeOptions(m_opModes.values().toArray(options));
1343    } finally {
1344      m_opModesMutex.unlock();
1345    }
1346
1347    var modeCounts =
1348        m_opModes.values().stream()
1349            .collect(Collectors.groupingBy(OpModeOption::getMode, Collectors.counting()));
1350
1351    for (RobotMode mode : RobotMode.values()) {
1352      HAL.reportUsage("OpMode/" + mode, String.valueOf(modeCounts.getOrDefault(mode, 0L)));
1353    }
1354  }
1355
1356  /** Clears all operating mode options and publishes an empty list to the driver station. */
1357  public static void clearOpModes() {
1358    m_opModesMutex.lock();
1359    try {
1360      m_opModes.clear();
1361      DriverStationJNI.setOpModeOptions(new OpModeOption[0]);
1362    } finally {
1363      m_opModesMutex.unlock();
1364    }
1365  }
1366
1367  /**
1368   * Sets the program starting flag in the DS. This will also allow {@link #getOpModeId()} and
1369   * {@link #getOpMode()} to return values for the selected OpMode in the DS application, if the DS
1370   * is connected by the time this method is called.
1371   *
1372   * <p>Most users will not need to use this method; the {@link TimedRobot} and {@link OpModeRobot}
1373   * robot framework classes will call it automatically after the main robot class is instantiated.
1374   * However, teams using the commandsv3 library and a custom main robot class need to be careful to
1375   * only call this method after all mechanisms and global trigger bindings are set up. If not, any
1376   * setup performed in the main robot class may be incorrectly bound to the opmode selected in the
1377   * DS if it's connected by the time the robot program boots up.
1378   *
1379   * <p>This is what changes the DS to showing robot code ready.
1380   *
1381   * @see #getOpMode()
1382   * @see #getOpModeId()
1383   */
1384  public static void observeUserProgramStarting() {
1385    m_userProgramStarted = true;
1386    DriverStationJNI.observeUserProgramStarting();
1387  }
1388
1389  /**
1390   * Gets the operating mode selected on the driver station. Note this does not mean the robot is
1391   * enabled; use isEnabled() for that. In a match, this will indicate the operating mode selected
1392   * for auto before the match starts (i.e., while the robot is disabled in auto mode); after the
1393   * auto period ends, this will change to reflect the operating mode selected for teleop.
1394   *
1395   * <p>This method always returns {@code 0} while the main robot class is being constructed and
1396   * initialized (more specifically, it returns {@code 0} until {@link
1397   * #observeUserProgramStarting()} is called, which the WPILib framework will automatically call
1398   * during {@link TimedRobot#startCompetition()} and {@link OpModeRobot#startCompetition()}).
1399   *
1400   * @return the unique ID provided by the addOpMode() function; may return 0 or a unique ID not
1401   *     added, so callers should be prepared to handle that case
1402   */
1403  public static long getOpModeId() {
1404    if (!m_userProgramStarted) {
1405      return 0;
1406    }
1407
1408    m_cacheDataMutex.lock();
1409    try {
1410      return m_controlWord.getOpModeId();
1411    } finally {
1412      m_cacheDataMutex.unlock();
1413    }
1414  }
1415
1416  /**
1417   * Gets the operating mode selected on the driver station. Note this does not mean the robot is
1418   * enabled; use isEnabled() for that. In a match, this will indicate the operating mode selected
1419   * for auto before the match starts (i.e., while the robot is disabled in auto mode); after the
1420   * auto period ends, this will change to reflect the operating mode selected for teleop.
1421   *
1422   * <p>This method always returns an empty string {@code ""} while the main robot class is being
1423   * constructed and initialized (more specifically, it returns {@code ""} until {@link
1424   * #observeUserProgramStarting()} is called, which the WPILib framework will automatically call
1425   * during {@link TimedRobot#startCompetition()} and {@link OpModeRobot#startCompetition()}).
1426   *
1427   * @return Operating mode string; may return a string not in the list of options, so callers
1428   *     should be prepared to handle that case
1429   */
1430  public static String getOpMode() {
1431    if (!m_userProgramStarted) {
1432      return "";
1433    }
1434
1435    m_cacheDataMutex.lock();
1436    try {
1437      return m_opMode;
1438    } finally {
1439      m_cacheDataMutex.unlock();
1440    }
1441  }
1442
1443  /**
1444   * Check to see if the selected operating mode is a particular value. Note this does not mean the
1445   * robot is enabled; use isEnabled() for that.
1446   *
1447   * @param id operating mode unique ID
1448   * @return True if that mode is the current mode
1449   */
1450  public static boolean isOpMode(long id) {
1451    return getOpModeId() == id;
1452  }
1453
1454  /**
1455   * Check to see if the selected operating mode is a particular value. Note this does not mean the
1456   * robot is enabled; use isEnabled() for that.
1457   *
1458   * @param mode operating mode
1459   * @return True if that mode is the current mode
1460   */
1461  public static boolean isOpMode(String mode) {
1462    return getOpMode().equals(mode);
1463  }
1464
1465  /**
1466   * Gets a value indicating whether the Driver Station is attached.
1467   *
1468   * @return True if Driver Station is attached, false otherwise.
1469   */
1470  public static boolean isDSAttached() {
1471    m_cacheDataMutex.lock();
1472    try {
1473      return m_controlWord.isDSAttached();
1474    } finally {
1475      m_cacheDataMutex.unlock();
1476    }
1477  }
1478
1479  /**
1480   * Gets if the driver station attached to a Field Management System.
1481   *
1482   * @return true if the robot is competing on a field being controlled by a Field Management System
1483   */
1484  public static boolean isFMSAttached() {
1485    m_cacheDataMutex.lock();
1486    try {
1487      return m_controlWord.isFMSAttached();
1488    } finally {
1489      m_cacheDataMutex.unlock();
1490    }
1491  }
1492
1493  /**
1494   * Get the game specific message from the FMS.
1495   *
1496   * <p>If the FMS is not connected, it is set from the game data setting on the driver station.
1497   *
1498   * @return the game specific message
1499   */
1500  public static Optional<String> getGameData() {
1501    m_cacheDataMutex.lock();
1502    try {
1503      if (m_gameData == null || m_gameData.isEmpty()) {
1504        return Optional.empty();
1505      }
1506      return Optional.of(m_gameData);
1507    } finally {
1508      m_cacheDataMutex.unlock();
1509    }
1510  }
1511
1512  /**
1513   * Get the event name from the FMS.
1514   *
1515   * @return the event name
1516   */
1517  public static String getEventName() {
1518    m_cacheDataMutex.lock();
1519    try {
1520      return m_matchInfo.eventName;
1521    } finally {
1522      m_cacheDataMutex.unlock();
1523    }
1524  }
1525
1526  /**
1527   * Get the match type from the FMS.
1528   *
1529   * @return the match type
1530   */
1531  public static MatchType getMatchType() {
1532    int matchType;
1533    m_cacheDataMutex.lock();
1534    try {
1535      matchType = m_matchInfo.matchType;
1536    } finally {
1537      m_cacheDataMutex.unlock();
1538    }
1539    return switch (matchType) {
1540      case 1 -> MatchType.PRACTICE;
1541      case 2 -> MatchType.QUALIFICATION;
1542      case 3 -> MatchType.ELIMINATION;
1543      default -> MatchType.NONE;
1544    };
1545  }
1546
1547  /**
1548   * Get the match number from the FMS.
1549   *
1550   * @return the match number
1551   */
1552  public static int getMatchNumber() {
1553    m_cacheDataMutex.lock();
1554    try {
1555      return m_matchInfo.matchNumber;
1556    } finally {
1557      m_cacheDataMutex.unlock();
1558    }
1559  }
1560
1561  /**
1562   * Get the replay number from the FMS.
1563   *
1564   * @return the replay number
1565   */
1566  public static int getReplayNumber() {
1567    m_cacheDataMutex.lock();
1568    try {
1569      return m_matchInfo.replayNumber;
1570    } finally {
1571      m_cacheDataMutex.unlock();
1572    }
1573  }
1574
1575  private static Map<AllianceStationID, Optional<Alliance>> m_allianceMap =
1576      Map.of(
1577          AllianceStationID.UNKNOWN, Optional.empty(),
1578          AllianceStationID.RED_1, Optional.of(Alliance.RED),
1579          AllianceStationID.RED_2, Optional.of(Alliance.RED),
1580          AllianceStationID.RED_3, Optional.of(Alliance.RED),
1581          AllianceStationID.BLUE_1, Optional.of(Alliance.BLUE),
1582          AllianceStationID.BLUE_2, Optional.of(Alliance.BLUE),
1583          AllianceStationID.BLUE_3, Optional.of(Alliance.BLUE));
1584
1585  private static Map<AllianceStationID, OptionalInt> m_stationMap =
1586      Map.of(
1587          AllianceStationID.UNKNOWN, OptionalInt.empty(),
1588          AllianceStationID.RED_1, OptionalInt.of(1),
1589          AllianceStationID.RED_2, OptionalInt.of(2),
1590          AllianceStationID.RED_3, OptionalInt.of(3),
1591          AllianceStationID.BLUE_1, OptionalInt.of(1),
1592          AllianceStationID.BLUE_2, OptionalInt.of(2),
1593          AllianceStationID.BLUE_3, OptionalInt.of(3));
1594
1595  /**
1596   * Get the current alliance from the FMS.
1597   *
1598   * <p>If the FMS is not connected, it is set from the team alliance setting on the driver station.
1599   *
1600   * @return The alliance (red or blue) or an empty optional if the alliance is invalid
1601   */
1602  public static Optional<Alliance> getAlliance() {
1603    AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation();
1604    if (allianceStationID == null) {
1605      allianceStationID = AllianceStationID.UNKNOWN;
1606    }
1607
1608    return m_allianceMap.get(allianceStationID);
1609  }
1610
1611  /**
1612   * Gets the location of the team's driver station controls from the FMS.
1613   *
1614   * <p>If the FMS is not connected, it is set from the team alliance setting on the driver station.
1615   *
1616   * @return the location of the team's driver station controls: 1, 2, or 3
1617   */
1618  public static OptionalInt getLocation() {
1619    AllianceStationID allianceStationID = DriverStationJNI.getAllianceStation();
1620    if (allianceStationID == null) {
1621      allianceStationID = AllianceStationID.UNKNOWN;
1622    }
1623
1624    return m_stationMap.get(allianceStationID);
1625  }
1626
1627  /**
1628   * Gets the raw alliance station of the teams driver station.
1629   *
1630   * <p>This returns the raw low level value. Prefer getLocation or getAlliance unless necessary for
1631   * performance.
1632   *
1633   * @return The raw alliance station id.
1634   */
1635  public static AllianceStationID getRawAllianceStation() {
1636    return DriverStationJNI.getAllianceStation();
1637  }
1638
1639  /**
1640   * Return the approximate match time. The FMS does not send an official match time to the robots,
1641   * but does send an approximate match time. The value will count down the time remaining in the
1642   * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to
1643   * dispute ref calls or guarantee that a function will trigger before the match ends).
1644   *
1645   * <p>When connected to the real field, this number only changes in full integer increments, and
1646   * always counts down.
1647   *
1648   * <p>When the DS is in practice mode, this number is a floating point number, and counts down.
1649   *
1650   * <p>When the DS is in teleop or autonomous mode, this number returns -1.0.
1651   *
1652   * <p>Simulation matches DS behavior without an FMS connected.
1653   *
1654   * @return Time remaining in current match period (auto or teleop) in seconds
1655   */
1656  public static double getMatchTime() {
1657    return DriverStationJNI.getMatchTime();
1658  }
1659
1660  /**
1661   * Allows the user to specify whether they want joystick connection warnings to be printed to the
1662   * console. This setting is ignored when the FMS is connected -- warnings will always be on in
1663   * that scenario.
1664   *
1665   * @param silence Whether warning messages should be silenced.
1666   */
1667  public static void silenceJoystickConnectionWarning(boolean silence) {
1668    m_silenceJoystickWarning = silence;
1669  }
1670
1671  /**
1672   * Returns whether joystick connection warnings are silenced. This will always return false when
1673   * connected to the FMS.
1674   *
1675   * @return Whether joystick connection warnings are silenced.
1676   */
1677  public static boolean isJoystickConnectionWarningSilenced() {
1678    return !isFMSAttached() && m_silenceJoystickWarning;
1679  }
1680
1681  /**
1682   * Refresh the passed in control word to contain the current control word cache.
1683   *
1684   * @param word Word to refresh.
1685   */
1686  public static void refreshControlWordFromCache(ControlWord word) {
1687    m_cacheDataMutex.lock();
1688    try {
1689      word.update(m_controlWord);
1690    } finally {
1691      m_cacheDataMutex.unlock();
1692    }
1693  }
1694
1695  /**
1696   * Copy data from the DS task for the user. If no new data exists, it will just be returned,
1697   * otherwise the data will be copied from the DS polling loop.
1698   */
1699  public static void refreshData() {
1700    DriverStationJNI.refreshDSData();
1701
1702    // Get the status of all the joysticks
1703    for (byte stick = 0; stick < JOYSTICK_PORTS; stick++) {
1704      DriverStationJNI.getAllJoystickData(
1705          stick,
1706          m_joystickAxesCache[stick].m_axes,
1707          m_joystickAxesRawCache[stick].m_axes,
1708          m_joystickPOVsCache[stick].m_povs,
1709          m_touchpadFingersCache,
1710          m_metadataCache);
1711      m_joystickAxesCache[stick].m_available = (int) m_metadataCache[0];
1712      m_joystickAxesRawCache[stick].m_available = (int) m_metadataCache[0];
1713      m_joystickPOVsCache[stick].m_available = (int) m_metadataCache[1];
1714      m_joystickButtonsCache[stick].m_available = m_metadataCache[2];
1715      m_joystickButtonsCache[stick].m_buttons = m_metadataCache[3];
1716      m_joystickTouchpadsCache[stick].m_count = (int) m_metadataCache[4];
1717      for (int i = 0; i < m_joystickTouchpadsCache[stick].m_count; i++) {
1718        long metadata = m_metadataCache[5 + i];
1719        m_joystickTouchpadsCache[stick].m_touchpads[i].m_fingers[0].m_down = (metadata & 0x1) != 0;
1720        m_joystickTouchpadsCache[stick].m_touchpads[i].m_fingers[1].m_down = (metadata & 0x2) != 0;
1721        m_joystickTouchpadsCache[stick].m_touchpads[i].m_count = (int) (metadata >> 2 & 0x3);
1722        for (int j = 0; j < m_joystickTouchpadsCache[stick].m_touchpads[i].m_count; j++) {
1723          m_joystickTouchpadsCache[stick].m_touchpads[i].m_fingers[j].m_x =
1724              m_touchpadFingersCache[i * 4 + j * 2 + 0];
1725          m_joystickTouchpadsCache[stick].m_touchpads[i].m_fingers[j].m_y =
1726              m_touchpadFingersCache[i * 4 + j * 2 + 1];
1727        }
1728      }
1729    }
1730
1731    DriverStationJNI.getMatchInfo(m_matchInfoCache);
1732
1733    // This is a pass through, so if it hasn't changed, it doesn't
1734    // reallocate
1735    m_gameDataCache = DriverStationJNI.getGameData(m_gameDataCache);
1736
1737    DriverStationJNI.getControlWord(m_controlWordCache);
1738
1739    m_opModeCache = opModeToString(m_controlWordCache.getOpModeId());
1740
1741    DataLogSender dataLogSender;
1742    // lock joystick mutex to swap cache data
1743    m_cacheDataMutex.lock();
1744    try {
1745      for (int i = 0; i < JOYSTICK_PORTS; i++) {
1746        // If buttons weren't pressed and are now, set flags in m_buttonsPressed
1747        m_joystickButtonsPressed[i] |=
1748            ~m_joystickButtons[i].m_buttons & m_joystickButtonsCache[i].m_buttons;
1749
1750        // If buttons were pressed and aren't now, set flags in m_buttonsReleased
1751        m_joystickButtonsReleased[i] |=
1752            m_joystickButtons[i].m_buttons & ~m_joystickButtonsCache[i].m_buttons;
1753      }
1754
1755      // move cache to actual data
1756      HALJoystickAxes[] currentAxes = m_joystickAxes;
1757      m_joystickAxes = m_joystickAxesCache;
1758      m_joystickAxesCache = currentAxes;
1759
1760      HALJoystickAxesRaw[] currentAxesRaw = m_joystickAxesRaw;
1761      m_joystickAxesRaw = m_joystickAxesRawCache;
1762      m_joystickAxesRawCache = currentAxesRaw;
1763
1764      HALJoystickButtons[] currentButtons = m_joystickButtons;
1765      m_joystickButtons = m_joystickButtonsCache;
1766      m_joystickButtonsCache = currentButtons;
1767
1768      HALJoystickPOVs[] currentPOVs = m_joystickPOVs;
1769      m_joystickPOVs = m_joystickPOVsCache;
1770      m_joystickPOVsCache = currentPOVs;
1771
1772      HALJoystickTouchpads[] currentTouchpads = m_joystickTouchpads;
1773      m_joystickTouchpads = m_joystickTouchpadsCache;
1774      m_joystickTouchpadsCache = currentTouchpads;
1775
1776      MatchInfoData currentInfo = m_matchInfo;
1777      m_matchInfo = m_matchInfoCache;
1778      m_matchInfoCache = currentInfo;
1779
1780      m_gameData = m_gameDataCache;
1781
1782      ControlWord currentWord = m_controlWord;
1783      m_controlWord = m_controlWordCache;
1784      m_controlWordCache = currentWord;
1785
1786      String currentOpMode = m_opMode;
1787      m_opMode = m_opModeCache;
1788      m_opModeCache = currentOpMode;
1789
1790      dataLogSender = m_dataLogSender;
1791    } finally {
1792      m_cacheDataMutex.unlock();
1793    }
1794
1795    m_refreshEvents.wakeup();
1796
1797    m_matchDataSender.sendMatchData();
1798    if (dataLogSender != null) {
1799      dataLogSender.send(WPIUtilJNI.now());
1800    }
1801  }
1802
1803  /**
1804   * Registers the given handle for DS data refresh notifications.
1805   *
1806   * @param handle The event handle.
1807   */
1808  public static void provideRefreshedDataEventHandle(int handle) {
1809    m_refreshEvents.add(handle);
1810  }
1811
1812  /**
1813   * Unregisters the given handle from DS data refresh notifications.
1814   *
1815   * @param handle The event handle.
1816   */
1817  public static void removeRefreshedDataEventHandle(int handle) {
1818    m_refreshEvents.remove(handle);
1819  }
1820
1821  /**
1822   * Reports errors related to joystick availability. Throttles the errors so that they don't
1823   * overwhelm the DS.
1824   *
1825   * @param stick The joystick port.
1826   * @param message The message to report if the joystick is connected.
1827   */
1828  private static void reportJoystickWarning(int stick, String message) {
1829    if (isFMSAttached() || !m_silenceJoystickWarning) {
1830      double currentTime = Timer.getTimestamp();
1831      if (currentTime > m_nextMessageTime) {
1832        if (isJoystickConnected(stick)) {
1833          reportWarning(message, false);
1834        } else {
1835          reportWarning(
1836              "Joystick on port " + stick + " not available, check if controller is plugged in",
1837              false);
1838        }
1839        m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
1840      }
1841    }
1842  }
1843
1844  /**
1845   * Starts logging DriverStation data to data log. Repeated calls are ignored.
1846   *
1847   * @param log data log
1848   * @param logJoysticks if true, log joystick data
1849   */
1850  @SuppressWarnings("PMD.NonThreadSafeSingleton")
1851  public static void startDataLog(DataLog log, boolean logJoysticks) {
1852    m_cacheDataMutex.lock();
1853    try {
1854      if (m_dataLogSender == null) {
1855        m_dataLogSender = new DataLogSender(log, logJoysticks, WPIUtilJNI.now());
1856      }
1857    } finally {
1858      m_cacheDataMutex.unlock();
1859    }
1860  }
1861
1862  /**
1863   * Starts logging DriverStation data to data log, including joystick data. Repeated calls are
1864   * ignored.
1865   *
1866   * @param log data log
1867   */
1868  public static void startDataLog(DataLog log) {
1869    startDataLog(log, true);
1870  }
1871}