001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.wpilibj;
006
007import edu.wpi.first.cameraserver.CameraServerShared;
008import edu.wpi.first.cameraserver.CameraServerSharedStore;
009import edu.wpi.first.hal.FRCNetComm.tInstances;
010import edu.wpi.first.hal.FRCNetComm.tResourceType;
011import edu.wpi.first.hal.HAL;
012import edu.wpi.first.hal.HALUtil;
013import edu.wpi.first.math.MathShared;
014import edu.wpi.first.math.MathSharedStore;
015import edu.wpi.first.math.MathUsageId;
016import edu.wpi.first.networktables.MultiSubscriber;
017import edu.wpi.first.networktables.NetworkTableEvent;
018import edu.wpi.first.networktables.NetworkTableInstance;
019import edu.wpi.first.util.WPIUtilJNI;
020import edu.wpi.first.wpilibj.livewindow.LiveWindow;
021import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
022import edu.wpi.first.wpilibj.util.WPILibVersion;
023import java.io.File;
024import java.io.IOException;
025import java.io.OutputStream;
026import java.nio.charset.StandardCharsets;
027import java.nio.file.Files;
028import java.util.concurrent.locks.ReentrantLock;
029import java.util.function.Supplier;
030
031/**
032 * Implement a Robot Program framework. The RobotBase class is intended to be subclassed to create a
033 * robot program. The user must implement {@link #startCompetition()}, which will be called once and
034 * is not expected to exit. The user must also implement {@link #endCompetition()}, which signals to
035 * the code in {@link #startCompetition()} that it should exit.
036 *
037 * <p>It is not recommended to subclass this class directly - instead subclass IterativeRobotBase or
038 * TimedRobot.
039 */
040public abstract class RobotBase implements AutoCloseable {
041  /** The ID of the main Java thread. */
042  // This is usually 1, but it is best to make sure
043  private static long m_threadId = -1;
044
045  private final MultiSubscriber m_suball;
046
047  private final int m_connListenerHandle;
048
049  private boolean m_dashboardDetected;
050
051  private static void setupCameraServerShared() {
052    CameraServerShared shared =
053        new CameraServerShared() {
054          @Override
055          public void reportVideoServer(int id) {
056            HAL.report(tResourceType.kResourceType_PCVideoServer, id + 1);
057          }
058
059          @Override
060          public void reportUsbCamera(int id) {
061            HAL.report(tResourceType.kResourceType_UsbCamera, id + 1);
062          }
063
064          @Override
065          public void reportDriverStationError(String error) {
066            DriverStation.reportError(error, true);
067          }
068
069          @Override
070          public void reportAxisCamera(int id) {
071            HAL.report(tResourceType.kResourceType_AxisCamera, id + 1);
072          }
073
074          @Override
075          public Long getRobotMainThreadId() {
076            return RobotBase.getMainThreadId();
077          }
078
079          @Override
080          public boolean isRoboRIO() {
081            return !RobotBase.isSimulation();
082          }
083        };
084
085    CameraServerSharedStore.setCameraServerShared(shared);
086  }
087
088  private static void setupMathShared() {
089    MathSharedStore.setMathShared(
090        new MathShared() {
091          @Override
092          public void reportError(String error, StackTraceElement[] stackTrace) {
093            DriverStation.reportError(error, stackTrace);
094          }
095
096          @Override
097          public void reportUsage(MathUsageId id, int count) {
098            switch (id) {
099              case kKinematics_DifferentialDrive -> HAL.report(
100                  tResourceType.kResourceType_Kinematics, tInstances.kKinematics_DifferentialDrive);
101              case kKinematics_MecanumDrive -> HAL.report(
102                  tResourceType.kResourceType_Kinematics, tInstances.kKinematics_MecanumDrive);
103              case kKinematics_SwerveDrive -> HAL.report(
104                  tResourceType.kResourceType_Kinematics, tInstances.kKinematics_SwerveDrive);
105              case kTrajectory_TrapezoidProfile -> HAL.report(
106                  tResourceType.kResourceType_TrapezoidProfile, count);
107              case kFilter_Linear -> HAL.report(tResourceType.kResourceType_LinearFilter, count);
108              case kOdometry_DifferentialDrive -> HAL.report(
109                  tResourceType.kResourceType_Odometry, tInstances.kOdometry_DifferentialDrive);
110              case kOdometry_SwerveDrive -> HAL.report(
111                  tResourceType.kResourceType_Odometry, tInstances.kOdometry_SwerveDrive);
112              case kOdometry_MecanumDrive -> HAL.report(
113                  tResourceType.kResourceType_Odometry, tInstances.kOdometry_MecanumDrive);
114              case kController_PIDController2 -> HAL.report(
115                  tResourceType.kResourceType_PIDController2, count);
116              case kController_ProfiledPIDController -> HAL.report(
117                  tResourceType.kResourceType_ProfiledPIDController, count);
118              case kController_BangBangController -> HAL.report(
119                  tResourceType.kResourceType_BangBangController, count);
120              case kTrajectory_PathWeaver -> HAL.report(
121                  tResourceType.kResourceType_PathWeaverTrajectory, count);
122              default -> {
123                // NOP
124              }
125            }
126          }
127
128          @Override
129          public double getTimestamp() {
130            return Timer.getTimestamp();
131          }
132        });
133  }
134
135  /**
136   * Constructor for a generic robot program. User code can be placed in the constructor that runs
137   * before the Autonomous or Operator Control period starts. The constructor will run to completion
138   * before Autonomous is entered.
139   *
140   * <p>This must be used to ensure that the communications code starts. In the future it would be
141   * nice to put this code into its own task that loads on boot so ensure that it runs.
142   */
143  protected RobotBase() {
144    final NetworkTableInstance inst = NetworkTableInstance.getDefault();
145    m_threadId = Thread.currentThread().getId();
146    setupCameraServerShared();
147    setupMathShared();
148    // subscribe to "" to force persistent values to propagate to local
149    m_suball = new MultiSubscriber(inst, new String[] {""});
150    if (!isSimulation()) {
151      inst.startServer("/home/lvuser/networktables.json");
152    } else {
153      inst.startServer();
154    }
155
156    // wait for the NT server to actually start
157    try {
158      int count = 0;
159      while (inst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kStarting)) {
160        Thread.sleep(10);
161        count++;
162        if (count > 100) {
163          throw new InterruptedException();
164        }
165      }
166    } catch (InterruptedException ex) {
167      System.err.println("timed out while waiting for NT server to start");
168    }
169
170    m_connListenerHandle =
171        inst.addConnectionListener(
172            false,
173            event -> {
174              if (event.is(NetworkTableEvent.Kind.kConnected)) {
175                if (event.connInfo.remote_id.startsWith("glass")) {
176                  HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Glass);
177                  m_dashboardDetected = true;
178                } else if (event.connInfo.remote_id.startsWith("SmartDashboard")) {
179                  HAL.report(
180                      tResourceType.kResourceType_Dashboard, tInstances.kDashboard_SmartDashboard);
181                  m_dashboardDetected = true;
182                } else if (event.connInfo.remote_id.startsWith("shuffleboard")) {
183                  HAL.report(
184                      tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Shuffleboard);
185                  m_dashboardDetected = true;
186                } else if (event.connInfo.remote_id.startsWith("elastic")
187                    || event.connInfo.remote_id.startsWith("Elastic")) {
188                  HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_Elastic);
189                  m_dashboardDetected = true;
190                } else if (event.connInfo.remote_id.startsWith("Dashboard")) {
191                  HAL.report(tResourceType.kResourceType_Dashboard, tInstances.kDashboard_LabVIEW);
192                  m_dashboardDetected = true;
193                } else if (event.connInfo.remote_id.startsWith("AdvantageScope")) {
194                  HAL.report(
195                      tResourceType.kResourceType_Dashboard, tInstances.kDashboard_AdvantageScope);
196                  m_dashboardDetected = true;
197                } else if (event.connInfo.remote_id.startsWith("QFRCDashboard")) {
198                  HAL.report(
199                      tResourceType.kResourceType_Dashboard, tInstances.kDashboard_QFRCDashboard);
200                  m_dashboardDetected = true;
201                } else if (event.connInfo.remote_id.startsWith("FRC Web Components")) {
202                  HAL.report(
203                      tResourceType.kResourceType_Dashboard,
204                      tInstances.kDashboard_FRCWebComponents);
205                  m_dashboardDetected = true;
206                } else {
207                  // Only report unknown if there wasn't another dashboard already reported
208                  // (unknown could also be another device)
209                  if (!m_dashboardDetected) {
210                    int delim = event.connInfo.remote_id.indexOf('@');
211                    if (delim != -1) {
212                      HAL.report(
213                          tResourceType.kResourceType_Dashboard,
214                          tInstances.kDashboard_Unknown,
215                          0,
216                          event.connInfo.remote_id.substring(0, delim));
217                    } else {
218                      HAL.report(
219                          tResourceType.kResourceType_Dashboard,
220                          tInstances.kDashboard_Unknown,
221                          0,
222                          event.connInfo.remote_id);
223                    }
224                  }
225                }
226              }
227            });
228
229    LiveWindow.setEnabled(false);
230    Shuffleboard.disableActuatorWidgets();
231  }
232
233  /**
234   * Returns the main thread ID.
235   *
236   * @return The main thread ID.
237   */
238  public static long getMainThreadId() {
239    return m_threadId;
240  }
241
242  @Override
243  public void close() {
244    m_suball.close();
245    NetworkTableInstance.getDefault().removeListener(m_connListenerHandle);
246  }
247
248  /**
249   * Get the current runtime type.
250   *
251   * @return Current runtime type.
252   */
253  public static RuntimeType getRuntimeType() {
254    return RuntimeType.getValue(HALUtil.getHALRuntimeType());
255  }
256
257  /**
258   * Get if the robot is a simulation.
259   *
260   * @return If the robot is running in simulation.
261   */
262  public static boolean isSimulation() {
263    return getRuntimeType() == RuntimeType.kSimulation;
264  }
265
266  /**
267   * Get if the robot is real.
268   *
269   * @return If the robot is running in the real world.
270   */
271  public static boolean isReal() {
272    RuntimeType runtimeType = getRuntimeType();
273    return runtimeType == RuntimeType.kRoboRIO || runtimeType == RuntimeType.kRoboRIO2;
274  }
275
276  /**
277   * Determine if the Robot is currently disabled.
278   *
279   * @return True if the Robot is currently disabled by the Driver Station.
280   */
281  public boolean isDisabled() {
282    return DriverStation.isDisabled();
283  }
284
285  /**
286   * Determine if the Robot is currently enabled.
287   *
288   * @return True if the Robot is currently enabled by the Driver Station.
289   */
290  public boolean isEnabled() {
291    return DriverStation.isEnabled();
292  }
293
294  /**
295   * Determine if the robot is currently in Autonomous mode as determined by the Driver Station.
296   *
297   * @return True if the robot is currently operating Autonomously.
298   */
299  public boolean isAutonomous() {
300    return DriverStation.isAutonomous();
301  }
302
303  /**
304   * Determine if the robot is currently in Autonomous mode and enabled as determined by the Driver
305   * Station.
306   *
307   * @return True if the robot is currently operating autonomously while enabled.
308   */
309  public boolean isAutonomousEnabled() {
310    return DriverStation.isAutonomousEnabled();
311  }
312
313  /**
314   * Determine if the robot is currently in Test mode as determined by the Driver Station.
315   *
316   * @return True if the robot is currently operating in Test mode.
317   */
318  public boolean isTest() {
319    return DriverStation.isTest();
320  }
321
322  /**
323   * Determine if the robot is current in Test mode and enabled as determined by the Driver Station.
324   *
325   * @return True if the robot is currently operating in Test mode while enabled.
326   */
327  public boolean isTestEnabled() {
328    return DriverStation.isTestEnabled();
329  }
330
331  /**
332   * Determine if the robot is currently in Operator Control mode as determined by the Driver
333   * Station.
334   *
335   * @return True if the robot is currently operating in Tele-Op mode.
336   */
337  public boolean isTeleop() {
338    return DriverStation.isTeleop();
339  }
340
341  /**
342   * Determine if the robot is currently in Operator Control mode and enabled as determined by the
343   * Driver Station.
344   *
345   * @return True if the robot is currently operating in Tele-Op mode while enabled.
346   */
347  public boolean isTeleopEnabled() {
348    return DriverStation.isTeleopEnabled();
349  }
350
351  /**
352   * Start the main robot code. This function will be called once and should not exit until
353   * signalled by {@link #endCompetition()}
354   */
355  public abstract void startCompetition();
356
357  /** Ends the main loop in {@link #startCompetition()}. */
358  public abstract void endCompetition();
359
360  private static final ReentrantLock m_runMutex = new ReentrantLock();
361  private static RobotBase m_robotCopy;
362  private static boolean m_suppressExitWarning;
363
364  /** Run the robot main loop. */
365  private static <T extends RobotBase> void runRobot(Supplier<T> robotSupplier) {
366    System.out.println("********** Robot program starting **********");
367
368    T robot;
369    try {
370      robot = robotSupplier.get();
371    } catch (Throwable throwable) {
372      Throwable cause = throwable.getCause();
373      if (cause != null) {
374        throwable = cause;
375      }
376      String robotName = "Unknown";
377      StackTraceElement[] elements = throwable.getStackTrace();
378      if (elements.length > 0) {
379        robotName = elements[0].getClassName();
380      }
381      DriverStation.reportError(
382          "Unhandled exception instantiating robot " + robotName + " " + throwable, elements);
383      DriverStation.reportError(
384          "The robot program quit unexpectedly."
385              + " This is usually due to a code error.\n"
386              + "  The above stacktrace can help determine where the error occurred.\n"
387              + "  See https://wpilib.org/stacktrace for more information.\n",
388          false);
389      DriverStation.reportError("Could not instantiate robot " + robotName + "!", false);
390      return;
391    }
392
393    m_runMutex.lock();
394    m_robotCopy = robot;
395    m_runMutex.unlock();
396
397    if (!isSimulation()) {
398      final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini");
399      try {
400        if (file.exists() && !file.delete()) {
401          throw new IOException("Failed to delete FRC_Lib_Version.ini");
402        }
403
404        if (!file.createNewFile()) {
405          throw new IOException("Failed to create new FRC_Lib_Version.ini");
406        }
407
408        try (OutputStream output = Files.newOutputStream(file.toPath())) {
409          output.write("Java ".getBytes(StandardCharsets.UTF_8));
410          output.write(WPILibVersion.Version.getBytes(StandardCharsets.UTF_8));
411        }
412      } catch (IOException ex) {
413        DriverStation.reportError("Could not write FRC_Lib_Version.ini: " + ex, ex.getStackTrace());
414      }
415    }
416
417    boolean errorOnExit = false;
418    try {
419      robot.startCompetition();
420    } catch (Throwable throwable) {
421      Throwable cause = throwable.getCause();
422      if (cause != null) {
423        throwable = cause;
424      }
425      DriverStation.reportError("Unhandled exception: " + throwable, throwable.getStackTrace());
426      errorOnExit = true;
427    } finally {
428      m_runMutex.lock();
429      boolean suppressExitWarning = m_suppressExitWarning;
430      m_runMutex.unlock();
431      if (!suppressExitWarning) {
432        // startCompetition never returns unless exception occurs....
433        DriverStation.reportWarning(
434            "The robot program quit unexpectedly."
435                + " This is usually due to a code error.\n"
436                + "  The above stacktrace can help determine where the error occurred.\n"
437                + "  See https://wpilib.org/stacktrace for more information.",
438            false);
439        if (errorOnExit) {
440          DriverStation.reportError(
441              "The startCompetition() method (or methods called by it) should have "
442                  + "handled the exception above.",
443              false);
444        } else {
445          DriverStation.reportError("Unexpected return from startCompetition() method.", false);
446        }
447      }
448    }
449  }
450
451  /**
452   * Suppress the "The robot program quit unexpectedly." message.
453   *
454   * @param value True if exit warning should be suppressed.
455   */
456  public static void suppressExitWarning(boolean value) {
457    m_runMutex.lock();
458    m_suppressExitWarning = value;
459    m_runMutex.unlock();
460  }
461
462  /**
463   * Starting point for the applications.
464   *
465   * @param <T> Robot subclass.
466   * @param robotSupplier Function that returns an instance of the robot subclass.
467   */
468  public static <T extends RobotBase> void startRobot(Supplier<T> robotSupplier) {
469    // Check that the MSVC runtime is valid.
470    WPIUtilJNI.checkMsvcRuntime();
471
472    if (!HAL.initialize(500, 0)) {
473      throw new IllegalStateException("Failed to initialize. Terminating");
474    }
475
476    // Force refresh DS data
477    DriverStation.refreshData();
478
479    HAL.report(
480        tResourceType.kResourceType_Language, tInstances.kLanguage_Java, 0, WPILibVersion.Version);
481
482    if (!Notifier.setHALThreadPriority(true, 40)) {
483      DriverStation.reportWarning("Setting HAL Notifier RT priority to 40 failed", false);
484    }
485
486    if (HAL.hasMain()) {
487      Thread thread =
488          new Thread(
489              () -> {
490                runRobot(robotSupplier);
491                HAL.exitMain();
492              },
493              "robot main");
494      thread.setDaemon(true);
495      thread.start();
496      HAL.runMain();
497      suppressExitWarning(true);
498      m_runMutex.lock();
499      RobotBase robot = m_robotCopy;
500      m_runMutex.unlock();
501      if (robot != null) {
502        robot.endCompetition();
503      }
504      try {
505        thread.join(1000);
506      } catch (InterruptedException ex) {
507        Thread.currentThread().interrupt();
508      }
509    } else {
510      runRobot(robotSupplier);
511    }
512
513    // On RIO, this will just terminate rather than shutting down cleanly (it's a no-op in sim).
514    // It's not worth the risk of hanging on shutdown when we want the code to restart as quickly
515    // as possible.
516    HAL.terminate();
517
518    HAL.shutdown();
519
520    System.exit(0);
521  }
522}