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