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.hal.DriverStationJNI;
008import edu.wpi.first.hal.FRCNetComm.tInstances;
009import edu.wpi.first.hal.FRCNetComm.tResourceType;
010import edu.wpi.first.hal.HAL;
011import edu.wpi.first.hal.NotifierJNI;
012import java.util.PriorityQueue;
013
014/**
015 * TimedRobot implements the IterativeRobotBase robot program framework.
016 *
017 * <p>The TimedRobot class is intended to be subclassed by a user creating a robot program.
018 *
019 * <p>periodic() functions from the base class are called on an interval by a Notifier instance.
020 */
021public class TimedRobot extends IterativeRobotBase {
022  @SuppressWarnings("MemberName")
023  static class Callback implements Comparable<Callback> {
024    public Runnable func;
025    public double period;
026    public double expirationTime;
027
028    /**
029     * Construct a callback container.
030     *
031     * @param func The callback to run.
032     * @param startTimeSeconds The common starting point for all callback scheduling in seconds.
033     * @param periodSeconds The period at which to run the callback in seconds.
034     * @param offsetSeconds The offset from the common starting time in seconds.
035     */
036    Callback(Runnable func, double startTimeSeconds, double periodSeconds, double offsetSeconds) {
037      this.func = func;
038      this.period = periodSeconds;
039      this.expirationTime =
040          startTimeSeconds
041              + offsetSeconds
042              + Math.floor((Timer.getFPGATimestamp() - startTimeSeconds) / this.period)
043                  * this.period
044              + this.period;
045    }
046
047    @Override
048    public boolean equals(Object rhs) {
049      if (rhs instanceof Callback) {
050        return Double.compare(expirationTime, ((Callback) rhs).expirationTime) == 0;
051      }
052      return false;
053    }
054
055    @Override
056    public int hashCode() {
057      return Double.hashCode(expirationTime);
058    }
059
060    @Override
061    public int compareTo(Callback rhs) {
062      // Elements with sooner expiration times are sorted as lesser. The head of
063      // Java's PriorityQueue is the least element.
064      return Double.compare(expirationTime, rhs.expirationTime);
065    }
066  }
067
068  /** Default loop period. */
069  public static final double kDefaultPeriod = 0.02;
070
071  // The C pointer to the notifier object. We don't use it directly, it is
072  // just passed to the JNI bindings.
073  private final int m_notifier = NotifierJNI.initializeNotifier();
074
075  private double m_startTime;
076
077  private final PriorityQueue<Callback> m_callbacks = new PriorityQueue<>();
078
079  /** Constructor for TimedRobot. */
080  protected TimedRobot() {
081    this(kDefaultPeriod);
082  }
083
084  /**
085   * Constructor for TimedRobot.
086   *
087   * @param period Period in seconds.
088   */
089  protected TimedRobot(double period) {
090    super(period);
091    m_startTime = Timer.getFPGATimestamp();
092    addPeriodic(this::loopFunc, period);
093    NotifierJNI.setNotifierName(m_notifier, "TimedRobot");
094
095    HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed);
096  }
097
098  @Override
099  public void close() {
100    NotifierJNI.stopNotifier(m_notifier);
101    NotifierJNI.cleanNotifier(m_notifier);
102  }
103
104  /** Provide an alternate "main loop" via startCompetition(). */
105  @Override
106  public void startCompetition() {
107    robotInit();
108
109    if (isSimulation()) {
110      simulationInit();
111    }
112
113    // Tell the DS that the robot is ready to be enabled
114    System.out.println("********** Robot program startup complete **********");
115    DriverStationJNI.observeUserProgramStarting();
116
117    // Loop forever, calling the appropriate mode-dependent function
118    while (true) {
119      // We don't have to check there's an element in the queue first because
120      // there's always at least one (the constructor adds one). It's reenqueued
121      // at the end of the loop.
122      var callback = m_callbacks.poll();
123
124      NotifierJNI.updateNotifierAlarm(m_notifier, (long) (callback.expirationTime * 1e6));
125
126      long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier);
127      if (curTime == 0) {
128        break;
129      }
130
131      callback.func.run();
132
133      callback.expirationTime += callback.period;
134      m_callbacks.add(callback);
135
136      // Process all other callbacks that are ready to run
137      while ((long) (m_callbacks.peek().expirationTime * 1e6) <= curTime) {
138        callback = m_callbacks.poll();
139
140        callback.func.run();
141
142        callback.expirationTime += callback.period;
143        m_callbacks.add(callback);
144      }
145    }
146  }
147
148  /** Ends the main loop in startCompetition(). */
149  @Override
150  public void endCompetition() {
151    NotifierJNI.stopNotifier(m_notifier);
152  }
153
154  /**
155   * Add a callback to run at a specific period.
156   *
157   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
158   * synchronously. Interactions between them are thread-safe.
159   *
160   * @param callback The callback to run.
161   * @param periodSeconds The period at which to run the callback in seconds.
162   */
163  public final void addPeriodic(Runnable callback, double periodSeconds) {
164    m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, 0.0));
165  }
166
167  /**
168   * Add a callback to run at a specific period with a starting time offset.
169   *
170   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
171   * synchronously. Interactions between them are thread-safe.
172   *
173   * @param callback The callback to run.
174   * @param periodSeconds The period at which to run the callback in seconds.
175   * @param offsetSeconds The offset from the common starting time in seconds. This is useful for
176   *     scheduling a callback in a different timeslot relative to TimedRobot.
177   */
178  public final void addPeriodic(Runnable callback, double periodSeconds, double offsetSeconds) {
179    m_callbacks.add(new Callback(callback, m_startTime, periodSeconds, offsetSeconds));
180  }
181}