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.framework;
006
007import java.lang.reflect.Constructor;
008import java.util.concurrent.locks.ReentrantLock;
009import org.wpilib.driverstation.DriverStation;
010import org.wpilib.hardware.hal.HAL;
011import org.wpilib.hardware.hal.HALUtil;
012import org.wpilib.math.util.MathShared;
013import org.wpilib.math.util.MathSharedStore;
014import org.wpilib.networktables.MultiSubscriber;
015import org.wpilib.networktables.NetworkTableEvent;
016import org.wpilib.networktables.NetworkTableInstance;
017import org.wpilib.system.Notifier;
018import org.wpilib.system.RuntimeType;
019import org.wpilib.system.Timer;
020import org.wpilib.system.WPILibVersion;
021import org.wpilib.util.WPIUtilJNI;
022import org.wpilib.vision.stream.CameraServerShared;
023import org.wpilib.vision.stream.CameraServerSharedStore;
024
025/**
026 * Implement a Robot Program framework. The RobotBase class is intended to be subclassed to create a
027 * robot program. The user must implement {@link #startCompetition()}, which will be called once and
028 * is not expected to exit. The user must also implement {@link #endCompetition()}, which signals to
029 * the code in {@link #startCompetition()} that it should exit.
030 *
031 * <p>It is not recommended to subclass this class directly - instead subclass IterativeRobotBase or
032 * TimedRobot.
033 */
034public abstract class RobotBase implements AutoCloseable {
035  /** The ID of the main Java thread. */
036  // This is usually 1, but it is best to make sure
037  private static long m_threadId = -1;
038
039  private final MultiSubscriber m_suball;
040
041  private final int m_connListenerHandle;
042
043  private static void setupCameraServerShared() {
044    CameraServerShared shared =
045        new CameraServerShared() {
046          @Override
047          public void reportUsage(String resource, String data) {
048            HAL.reportUsage(resource, data);
049          }
050
051          @Override
052          public void reportDriverStationError(String error) {
053            DriverStation.reportError(error, true);
054          }
055
056          @Override
057          public Long getRobotMainThreadId() {
058            return RobotBase.getMainThreadId();
059          }
060
061          @Override
062          public boolean isRoboRIO() {
063            return !RobotBase.isSimulation();
064          }
065        };
066
067    CameraServerSharedStore.setCameraServerShared(shared);
068  }
069
070  private static void setupMathShared() {
071    MathSharedStore.setMathShared(
072        new MathShared() {
073          @Override
074          public void reportError(String error, StackTraceElement[] stackTrace) {
075            DriverStation.reportError(error, stackTrace);
076          }
077
078          @Override
079          public void reportUsage(String resource, String data) {
080            HAL.reportUsage(resource, data);
081          }
082
083          @Override
084          public double getTimestamp() {
085            return Timer.getTimestamp();
086          }
087        });
088  }
089
090  /**
091   * Constructor for a generic robot program. User code can be placed in the constructor that runs
092   * before the Autonomous or Operator Control period starts. The constructor will run to completion
093   * before Autonomous is entered.
094   *
095   * <p>This must be used to ensure that the communications code starts. In the future it would be
096   * nice to put this code into its own task that loads on boot so ensure that it runs.
097   */
098  protected RobotBase() {
099    final NetworkTableInstance inst = NetworkTableInstance.getDefault();
100    m_threadId = Thread.currentThread().threadId();
101    setupCameraServerShared();
102    setupMathShared();
103    // subscribe to "" to force persistent values to propagate to local
104    m_suball = new MultiSubscriber(inst, new String[] {""});
105    if (!isSimulation()) {
106      inst.startServer("/home/systemcore/networktables.json", "", "robot");
107    } else {
108      inst.startServer("networktables.json", "", "robot");
109    }
110
111    // wait for the NT server to actually start
112    try {
113      int count = 0;
114      while (inst.getNetworkMode().contains(NetworkTableInstance.NetworkMode.kStarting)) {
115        Thread.sleep(10);
116        count++;
117        if (count > 100) {
118          throw new InterruptedException();
119        }
120      }
121    } catch (InterruptedException ex) {
122      System.err.println("timed out while waiting for NT server to start");
123    }
124
125    m_connListenerHandle =
126        inst.addConnectionListener(
127            false,
128            event -> {
129              if (event.is(NetworkTableEvent.Kind.kConnected)) {
130                HAL.reportUsage("NT/" + event.connInfo.remote_id, "");
131              }
132            });
133  }
134
135  /**
136   * Returns the main thread ID.
137   *
138   * @return The main thread ID.
139   */
140  public static long getMainThreadId() {
141    return m_threadId;
142  }
143
144  @Override
145  public void close() {
146    m_suball.close();
147    NetworkTableInstance.getDefault().removeListener(m_connListenerHandle);
148  }
149
150  /**
151   * Get the current runtime type.
152   *
153   * @return Current runtime type.
154   */
155  public static RuntimeType getRuntimeType() {
156    return RuntimeType.getValue(HALUtil.getHALRuntimeType());
157  }
158
159  /**
160   * Get if the robot is a simulation.
161   *
162   * @return If the robot is running in simulation.
163   */
164  public static boolean isSimulation() {
165    return getRuntimeType() == RuntimeType.kSimulation;
166  }
167
168  /**
169   * Get if the robot is real.
170   *
171   * @return If the robot is running in the real world.
172   */
173  public static boolean isReal() {
174    RuntimeType runtimeType = getRuntimeType();
175    return runtimeType == RuntimeType.kSystemcore;
176  }
177
178  /**
179   * Determine if the Robot is currently disabled.
180   *
181   * @return True if the Robot is currently disabled by the Driver Station.
182   */
183  public static boolean isDisabled() {
184    return DriverStation.isDisabled();
185  }
186
187  /**
188   * Determine if the Robot is currently enabled.
189   *
190   * @return True if the Robot is currently enabled by the Driver Station.
191   */
192  public static boolean isEnabled() {
193    return DriverStation.isEnabled();
194  }
195
196  /**
197   * Determine if the robot is currently in Autonomous mode as determined by the Driver Station.
198   *
199   * @return True if the robot is currently operating Autonomously.
200   */
201  public static boolean isAutonomous() {
202    return DriverStation.isAutonomous();
203  }
204
205  /**
206   * Determine if the robot is currently in Autonomous mode and enabled as determined by the Driver
207   * Station.
208   *
209   * @return True if the robot is currently operating autonomously while enabled.
210   */
211  public static boolean isAutonomousEnabled() {
212    return DriverStation.isAutonomousEnabled();
213  }
214
215  /**
216   * Determine if the robot is currently in Test mode as determined by the Driver Station.
217   *
218   * @return True if the robot is currently operating in Test mode.
219   */
220  public static boolean isTest() {
221    return DriverStation.isTest();
222  }
223
224  /**
225   * Determine if the robot is current in Test mode and enabled as determined by the Driver Station.
226   *
227   * @return True if the robot is currently operating in Test mode while enabled.
228   */
229  public static boolean isTestEnabled() {
230    return DriverStation.isTestEnabled();
231  }
232
233  /**
234   * Determine if the robot is currently in Operator Control mode as determined by the Driver
235   * Station.
236   *
237   * @return True if the robot is currently operating in Tele-Op mode.
238   */
239  public static boolean isTeleop() {
240    return DriverStation.isTeleop();
241  }
242
243  /**
244   * Determine if the robot is currently in Operator Control mode and enabled as determined by the
245   * Driver Station.
246   *
247   * @return True if the robot is currently operating in Tele-Op mode while enabled.
248   */
249  public static boolean isTeleopEnabled() {
250    return DriverStation.isTeleopEnabled();
251  }
252
253  /**
254   * Gets the currently selected operating mode of the driver station. Note this does not mean the
255   * robot is enabled; use isEnabled() for that.
256   *
257   * @return the unique ID provided by the DriverStation.addOpMode() function; may return 0 or a
258   *     unique ID not added, so callers should be prepared to handle that case
259   */
260  public static long getOpModeId() {
261    return DriverStation.getOpModeId();
262  }
263
264  /**
265   * Gets the currently selected operating mode of the driver station. Note this does not mean the
266   * robot is enabled; use isEnabled() for that.
267   *
268   * @return Operating mode string; may return a string not in the list of options, so callers
269   *     should be prepared to handle that case
270   */
271  public static String getOpMode() {
272    return DriverStation.getOpMode();
273  }
274
275  /**
276   * Start the main robot code. This function will be called once and should not exit until
277   * signalled by {@link #endCompetition()}
278   */
279  public abstract void startCompetition();
280
281  /** Ends the main loop in {@link #startCompetition()}. */
282  public abstract void endCompetition();
283
284  private static final ReentrantLock m_runMutex = new ReentrantLock();
285  private static RobotBase m_robotCopy;
286  private static boolean m_suppressExitWarning;
287
288  private static <T extends RobotBase> T constructRobot(Class<T> robotClass) throws Throwable {
289    Constructor<?>[] constructors = robotClass.getConstructors();
290    Constructor<?> defaultConstructor = null;
291    for (Constructor<?> constructor : constructors) {
292      Class<?>[] paramTypes = constructor.getParameterTypes();
293      if (paramTypes.length == 0) {
294        if (defaultConstructor != null) {
295          throw new IllegalArgumentException(
296              "Multiple default constructors found in robot class " + robotClass.getName());
297        }
298        defaultConstructor = constructor;
299      }
300    }
301
302    T robot;
303
304    if (defaultConstructor != null) {
305      robot = robotClass.cast(defaultConstructor.newInstance());
306    } else {
307      throw new IllegalArgumentException(
308          "No valid constructor found in robot class " + robotClass.getName());
309    }
310
311    return robot;
312  }
313
314  /** Run the robot main loop. */
315  private static <T extends RobotBase> void runRobot(Class<T> robotClass) {
316    System.out.println("********** Robot program starting **********");
317
318    T robot;
319    try {
320      robot = constructRobot(robotClass);
321    } catch (Throwable throwable) {
322      Throwable cause = throwable.getCause();
323      if (cause != null) {
324        throwable = cause;
325      }
326      String robotName = "Unknown";
327      StackTraceElement[] elements = throwable.getStackTrace();
328      if (elements.length > 0) {
329        robotName = elements[0].getClassName();
330      }
331      DriverStation.reportError(
332          "Unhandled exception instantiating robot " + robotName + " " + throwable, elements);
333      DriverStation.reportError(
334          "The robot program quit unexpectedly."
335              + " This is usually due to a code error.\n"
336              + "  The above stacktrace can help determine where the error occurred.\n"
337              + "  See https://wpilib.org/stacktrace for more information.\n",
338          false);
339      DriverStation.reportError("Could not instantiate robot " + robotName + "!", false);
340      return;
341    }
342
343    m_runMutex.lock();
344    m_robotCopy = robot;
345    m_runMutex.unlock();
346
347    boolean errorOnExit = false;
348    try {
349      robot.startCompetition();
350    } catch (Throwable throwable) {
351      Throwable cause = throwable.getCause();
352      if (cause != null) {
353        throwable = cause;
354      }
355      DriverStation.reportError("Unhandled exception: " + throwable, throwable.getStackTrace());
356      errorOnExit = true;
357    } finally {
358      m_runMutex.lock();
359      boolean suppressExitWarning = m_suppressExitWarning;
360      m_runMutex.unlock();
361      if (!suppressExitWarning) {
362        // startCompetition never returns unless exception occurs....
363        DriverStation.reportWarning(
364            "The robot program quit unexpectedly."
365                + " This is usually due to a code error.\n"
366                + "  The above stacktrace can help determine where the error occurred.\n"
367                + "  See https://wpilib.org/stacktrace for more information.",
368            false);
369        if (errorOnExit) {
370          DriverStation.reportError(
371              "The startCompetition() method (or methods called by it) should have "
372                  + "handled the exception above.",
373              false);
374        } else {
375          DriverStation.reportError("Unexpected return from startCompetition() method.", false);
376        }
377      }
378    }
379  }
380
381  /**
382   * Suppress the "The robot program quit unexpectedly." message.
383   *
384   * @param value True if exit warning should be suppressed.
385   */
386  public static void suppressExitWarning(boolean value) {
387    m_runMutex.lock();
388    m_suppressExitWarning = value;
389    m_runMutex.unlock();
390  }
391
392  /**
393   * Starting point for the applications.
394   *
395   * @param robotClass Robot subclass type.
396   */
397  public static void startRobot(Class<? extends RobotBase> robotClass) {
398    // Check that the MSVC runtime is valid.
399    WPIUtilJNI.checkMsvcRuntime();
400
401    if (!HAL.initialize(500, 0)) {
402      throw new IllegalStateException("Failed to initialize. Terminating");
403    }
404
405    // Force refresh DS data
406    DriverStation.refreshData();
407
408    HAL.reportUsage("Language", "Java");
409    HAL.reportUsage("WPILibVersion", WPILibVersion.Version);
410
411    if (!Notifier.setHALThreadPriority(true, 40)) {
412      DriverStation.reportWarning("Setting HAL Notifier RT priority to 40 failed", false);
413    }
414
415    if (HAL.hasMain()) {
416      Thread thread =
417          new Thread(
418              () -> {
419                runRobot(robotClass);
420                HAL.exitMain();
421              },
422              "robot main");
423      thread.setDaemon(true);
424      thread.start();
425      HAL.runMain();
426      suppressExitWarning(true);
427      m_runMutex.lock();
428      RobotBase robot = m_robotCopy;
429      m_runMutex.unlock();
430      if (robot != null) {
431        robot.endCompetition();
432      }
433      try {
434        thread.join(1000);
435      } catch (InterruptedException ex) {
436        Thread.currentThread().interrupt();
437      }
438    } else {
439      runRobot(robotClass);
440    }
441
442    // On RIO, this will just terminate rather than shutting down cleanly (it's a no-op in sim).
443    // It's not worth the risk of hanging on shutdown when we want the code to restart as quickly
444    // as possible.
445    HAL.terminate();
446
447    HAL.shutdown();
448
449    System.exit(0);
450  }
451}