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 static org.wpilib.units.Units.Seconds;
008
009import java.util.PriorityQueue;
010import org.wpilib.hardware.hal.DriverStationJNI;
011import org.wpilib.hardware.hal.HAL;
012import org.wpilib.hardware.hal.NotifierJNI;
013import org.wpilib.system.RobotController;
014import org.wpilib.units.measure.Frequency;
015import org.wpilib.units.measure.Time;
016import org.wpilib.util.WPIUtilJNI;
017
018/**
019 * TimedRobot implements the IterativeRobotBase robot program framework.
020 *
021 * <p>The TimedRobot class is intended to be subclassed by a user creating a robot program.
022 *
023 * <p>periodic() functions from the base class are called on an interval by a Notifier instance.
024 */
025public class TimedRobot extends IterativeRobotBase {
026  @SuppressWarnings("MemberName")
027  static class Callback implements Comparable<Callback> {
028    public Runnable func;
029    public long period;
030    public long expirationTime;
031
032    /**
033     * Construct a callback container.
034     *
035     * @param func The callback to run.
036     * @param startTime The common starting point for all callback scheduling in microseconds.
037     * @param period The period at which to run the callback in microseconds.
038     * @param offset The offset from the common starting time in microseconds.
039     */
040    Callback(Runnable func, long startTime, long period, long offset) {
041      this.func = func;
042      this.period = period;
043      this.expirationTime =
044          startTime
045              + offset
046              + this.period
047              + (RobotController.getFPGATime() - startTime) / this.period * this.period;
048    }
049
050    @Override
051    public boolean equals(Object rhs) {
052      return rhs instanceof Callback callback && expirationTime == callback.expirationTime;
053    }
054
055    @Override
056    public int hashCode() {
057      return Long.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 Long.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.createNotifier();
074
075  private long m_startTimeUs;
076  private long m_loopStartTimeUs;
077
078  private final PriorityQueue<Callback> m_callbacks = new PriorityQueue<>();
079
080  /** Constructor for TimedRobot. */
081  protected TimedRobot() {
082    this(kDefaultPeriod);
083  }
084
085  /**
086   * Constructor for TimedRobot.
087   *
088   * @param period The period of the robot loop function.
089   */
090  protected TimedRobot(double period) {
091    super(period);
092    m_startTimeUs = RobotController.getFPGATime();
093    addPeriodic(this::loopFunc, period);
094    NotifierJNI.setNotifierName(m_notifier, "TimedRobot");
095
096    HAL.reportUsage("Framework", "TimedRobot");
097  }
098
099  /**
100   * Constructor for TimedRobot.
101   *
102   * @param period The period of the robot loop function.
103   */
104  protected TimedRobot(Time period) {
105    this(period.in(Seconds));
106  }
107
108  /**
109   * Constructor for TimedRobot.
110   *
111   * @param frequency The frequency of the robot loop function.
112   */
113  protected TimedRobot(Frequency frequency) {
114    this(frequency.asPeriod());
115  }
116
117  @Override
118  public void close() {
119    NotifierJNI.destroyNotifier(m_notifier);
120  }
121
122  /** Provide an alternate "main loop" via startCompetition(). */
123  @Override
124  public void startCompetition() {
125    if (isSimulation()) {
126      simulationInit();
127    }
128
129    // Tell the DS that the robot is ready to be enabled
130    System.out.println("********** Robot program startup complete **********");
131    DriverStationJNI.observeUserProgramStarting();
132
133    // Loop forever, calling the appropriate mode-dependent function
134    while (true) {
135      // We don't have to check there's an element in the queue first because
136      // there's always at least one (the constructor adds one). It's reenqueued
137      // at the end of the loop.
138      var callback = m_callbacks.poll();
139
140      NotifierJNI.setNotifierAlarm(m_notifier, callback.expirationTime, 0, true, true);
141
142      try {
143        WPIUtilJNI.waitForObject(m_notifier);
144      } catch (InterruptedException ex) {
145        Thread.currentThread().interrupt();
146        break;
147      }
148
149      long currentTime = RobotController.getFPGATime();
150      m_loopStartTimeUs = currentTime;
151
152      callback.func.run();
153
154      // Increment the expiration time by the number of full periods it's behind
155      // plus one to avoid rapid repeat fires from a large loop overrun. We
156      // assume currentTime ≥ expirationTime rather than checking for it since
157      // the callback wouldn't be running otherwise.
158      callback.expirationTime +=
159          callback.period
160              + (currentTime - callback.expirationTime) / callback.period * callback.period;
161      m_callbacks.add(callback);
162
163      // Process all other callbacks that are ready to run
164      while (m_callbacks.peek().expirationTime <= currentTime) {
165        callback = m_callbacks.poll();
166
167        callback.func.run();
168
169        callback.expirationTime +=
170            callback.period
171                + (currentTime - callback.expirationTime) / callback.period * callback.period;
172        m_callbacks.add(callback);
173      }
174    }
175  }
176
177  /** Ends the main loop in startCompetition(). */
178  @Override
179  public void endCompetition() {
180    NotifierJNI.destroyNotifier(m_notifier);
181  }
182
183  /**
184   * Return the system clock time in microseconds for the start of the current periodic loop. This
185   * is in the same time base as Timer.getFPGATimestamp(), but is stable through a loop. It is
186   * updated at the beginning of every periodic callback (including the normal periodic loop).
187   *
188   * @return Robot running time in microseconds, as of the start of the current periodic function.
189   */
190  public long getLoopStartTime() {
191    return m_loopStartTimeUs;
192  }
193
194  /**
195   * Add a callback to run at a specific period.
196   *
197   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
198   * synchronously. Interactions between them are thread-safe.
199   *
200   * @param callback The callback to run.
201   * @param period The period at which to run the callback in seconds.
202   */
203  public final void addPeriodic(Runnable callback, double period) {
204    m_callbacks.add(new Callback(callback, m_startTimeUs, (long) (period * 1e6), 0));
205  }
206
207  /**
208   * Add a callback to run at a specific period with a starting time offset.
209   *
210   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
211   * synchronously. Interactions between them are thread-safe.
212   *
213   * @param callback The callback to run.
214   * @param period The period at which to run the callback in seconds.
215   * @param offset The offset from the common starting time in seconds. This is useful for
216   *     scheduling a callback in a different timeslot relative to TimedRobot.
217   */
218  public final void addPeriodic(Runnable callback, double period, double offset) {
219    m_callbacks.add(
220        new Callback(callback, m_startTimeUs, (long) (period * 1e6), (long) (offset * 1e6)));
221  }
222
223  /**
224   * Add a callback to run at a specific period.
225   *
226   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
227   * synchronously. Interactions between them are thread-safe.
228   *
229   * @param callback The callback to run.
230   * @param period The period at which to run the callback.
231   */
232  public final void addPeriodic(Runnable callback, Time period) {
233    addPeriodic(callback, period.in(Seconds));
234  }
235
236  /**
237   * Add a callback to run at a specific period with a starting time offset.
238   *
239   * <p>This is scheduled on TimedRobot's Notifier, so TimedRobot and the callback run
240   * synchronously. Interactions between them are thread-safe.
241   *
242   * @param callback The callback to run.
243   * @param period The period at which to run the callback.
244   * @param offset The offset from the common starting time. This is useful for scheduling a
245   *     callback in a different timeslot relative to TimedRobot.
246   */
247  public final void addPeriodic(Runnable callback, Time period, Time offset) {
248    addPeriodic(callback, period.in(Seconds), offset.in(Seconds));
249  }
250}