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 org.wpilib.driverstation.DriverStation;
008import org.wpilib.hardware.hal.ControlWord;
009import org.wpilib.hardware.hal.DriverStationJNI;
010import org.wpilib.hardware.hal.HAL;
011import org.wpilib.hardware.hal.RobotMode;
012import org.wpilib.networktables.NetworkTableInstance;
013import org.wpilib.smartdashboard.SmartDashboard;
014import org.wpilib.system.Watchdog;
015
016/**
017 * IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase
018 * class.
019 *
020 * <p>The IterativeRobotBase class does not implement startCompetition(), so it should not be used
021 * by teams directly.
022 *
023 * <p>This class provides the following functions which are called by the main loop,
024 * startCompetition(), at the appropriate times:
025 *
026 * <p>driverStationConnected() -- provide for initialization the first time the DS is connected
027 *
028 * <p>init() functions -- each of the following functions is called once when the appropriate mode
029 * is entered:
030 *
031 * <ul>
032 *   <li>disabledInit() -- called each and every time disabled is entered from another mode
033 *   <li>autonomousInit() -- called each and every time autonomous is entered from another mode
034 *   <li>teleopInit() -- called each and every time teleop is entered from another mode
035 *   <li>testInit() -- called each and every time test is entered from another mode
036 * </ul>
037 *
038 * <p>periodic() functions -- each of these functions is called on an interval:
039 *
040 * <ul>
041 *   <li>robotPeriodic()
042 *   <li>disabledPeriodic()
043 *   <li>autonomousPeriodic()
044 *   <li>teleopPeriodic()
045 *   <li>testPeriodic()
046 * </ul>
047 *
048 * <p>exit() functions -- each of the following functions is called once when the appropriate mode
049 * is exited:
050 *
051 * <ul>
052 *   <li>disabledExit() -- called each and every time disabled is exited
053 *   <li>autonomousExit() -- called each and every time autonomous is exited
054 *   <li>teleopExit() -- called each and every time teleop is exited
055 *   <li>testExit() -- called each and every time test is exited
056 * </ul>
057 */
058public abstract class IterativeRobotBase extends RobotBase {
059  private final ControlWord m_word = new ControlWord();
060  private RobotMode m_lastMode;
061  private final double m_period;
062  private final Watchdog m_watchdog;
063  private boolean m_ntFlushEnabled = true;
064  private boolean m_calledDsConnected;
065
066  /**
067   * Constructor for IterativeRobotBase.
068   *
069   * @param period Period in seconds.
070   */
071  protected IterativeRobotBase(double period) {
072    m_period = period;
073    m_watchdog = new Watchdog(period, this::printLoopOverrunMessage);
074  }
075
076  /** Provide an alternate "main loop" via startCompetition(). */
077  @Override
078  public abstract void startCompetition();
079
080  /* ----------- Overridable initialization code ----------------- */
081
082  /**
083   * Code that needs to know the DS state should go here.
084   *
085   * <p>Users should override this method for initialization that needs to occur after the DS is
086   * connected, such as needing the alliance information.
087   */
088  public void driverStationConnected() {}
089
090  /**
091   * Robot-wide simulation initialization code should go here.
092   *
093   * <p>Users should override this method for default Robot-wide simulation related initialization
094   * which will be called when the robot is first started. It will be called exactly one time after
095   * the robot class constructor is called only when the robot is in simulation.
096   */
097  public void simulationInit() {}
098
099  /**
100   * Initialization code for disabled mode should go here.
101   *
102   * <p>Users should override this method for initialization code which will be called each time the
103   * robot enters disabled mode.
104   */
105  public void disabledInit() {}
106
107  /**
108   * Initialization code for autonomous mode should go here.
109   *
110   * <p>Users should override this method for initialization code which will be called each time the
111   * robot enters autonomous mode.
112   */
113  public void autonomousInit() {}
114
115  /**
116   * Initialization code for teleop mode should go here.
117   *
118   * <p>Users should override this method for initialization code which will be called each time the
119   * robot enters teleop mode.
120   */
121  public void teleopInit() {}
122
123  /**
124   * Initialization code for test mode should go here.
125   *
126   * <p>Users should override this method for initialization code which will be called each time the
127   * robot enters test mode.
128   */
129  public void testInit() {}
130
131  /* ----------- Overridable periodic code ----------------- */
132
133  private boolean m_rpFirstRun = true;
134
135  /** Periodic code for all robot modes should go here. */
136  public void robotPeriodic() {
137    if (m_rpFirstRun) {
138      System.out.println("Default robotPeriodic() method... Override me!");
139      m_rpFirstRun = false;
140    }
141  }
142
143  private boolean m_spFirstRun = true;
144
145  /**
146   * Periodic simulation code should go here.
147   *
148   * <p>This function is called in a simulated robot after user code executes.
149   */
150  public void simulationPeriodic() {
151    if (m_spFirstRun) {
152      System.out.println("Default simulationPeriodic() method... Override me!");
153      m_spFirstRun = false;
154    }
155  }
156
157  private boolean m_dpFirstRun = true;
158
159  /** Periodic code for disabled mode should go here. */
160  public void disabledPeriodic() {
161    if (m_dpFirstRun) {
162      System.out.println("Default disabledPeriodic() method... Override me!");
163      m_dpFirstRun = false;
164    }
165  }
166
167  private boolean m_apFirstRun = true;
168
169  /** Periodic code for autonomous mode should go here. */
170  public void autonomousPeriodic() {
171    if (m_apFirstRun) {
172      System.out.println("Default autonomousPeriodic() method... Override me!");
173      m_apFirstRun = false;
174    }
175  }
176
177  private boolean m_tpFirstRun = true;
178
179  /** Periodic code for teleop mode should go here. */
180  public void teleopPeriodic() {
181    if (m_tpFirstRun) {
182      System.out.println("Default teleopPeriodic() method... Override me!");
183      m_tpFirstRun = false;
184    }
185  }
186
187  private boolean m_tmpFirstRun = true;
188
189  /** Periodic code for test mode should go here. */
190  public void testPeriodic() {
191    if (m_tmpFirstRun) {
192      System.out.println("Default testPeriodic() method... Override me!");
193      m_tmpFirstRun = false;
194    }
195  }
196
197  /**
198   * Exit code for disabled mode should go here.
199   *
200   * <p>Users should override this method for code which will be called each time the robot exits
201   * disabled mode.
202   */
203  public void disabledExit() {}
204
205  /**
206   * Exit code for autonomous mode should go here.
207   *
208   * <p>Users should override this method for code which will be called each time the robot exits
209   * autonomous mode.
210   */
211  public void autonomousExit() {}
212
213  /**
214   * Exit code for teleop mode should go here.
215   *
216   * <p>Users should override this method for code which will be called each time the robot exits
217   * teleop mode.
218   */
219  public void teleopExit() {}
220
221  /**
222   * Exit code for test mode should go here.
223   *
224   * <p>Users should override this method for code which will be called each time the robot exits
225   * test mode.
226   */
227  public void testExit() {}
228
229  /**
230   * Enables or disables flushing NetworkTables every loop iteration. By default, this is enabled.
231   *
232   * @param enabled True to enable, false to disable
233   * @deprecated Deprecated without replacement.
234   */
235  @Deprecated(forRemoval = true, since = "2025")
236  public void setNetworkTablesFlushEnabled(boolean enabled) {
237    m_ntFlushEnabled = enabled;
238  }
239
240  /**
241   * Gets time period between calls to Periodic() functions.
242   *
243   * @return The time period between calls to Periodic() functions.
244   */
245  public double getPeriod() {
246    return m_period;
247  }
248
249  /** Loop function. */
250  protected void loopFunc() {
251    DriverStation.refreshData();
252    DriverStation.refreshControlWordFromCache(m_word);
253    m_watchdog.reset();
254
255    // Get current mode; treat disabled as unknown
256    boolean enabled = m_word.isEnabled();
257    RobotMode mode = enabled ? m_word.getRobotMode() : RobotMode.UNKNOWN;
258
259    if (!m_calledDsConnected && m_word.isDSAttached()) {
260      m_calledDsConnected = true;
261      driverStationConnected();
262    }
263
264    // If mode changed, call mode exit and entry functions
265    if (m_lastMode != mode) {
266      if (m_lastMode != null) {
267        // Call last mode's exit function
268        switch (m_lastMode) {
269          case UNKNOWN -> disabledExit();
270          case AUTONOMOUS -> autonomousExit();
271          case TELEOPERATED -> teleopExit();
272          case TEST -> testExit();
273          default -> {
274            // NOP
275          }
276        }
277      }
278
279      // Call current mode's entry function
280      switch (mode) {
281        case UNKNOWN -> {
282          disabledInit();
283          m_watchdog.addEpoch("disabledInit()");
284        }
285        case AUTONOMOUS -> {
286          autonomousInit();
287          m_watchdog.addEpoch("autonomousInit()");
288        }
289        case TELEOPERATED -> {
290          teleopInit();
291          m_watchdog.addEpoch("teleopInit()");
292        }
293        case TEST -> {
294          testInit();
295          m_watchdog.addEpoch("testInit()");
296        }
297        default -> {
298          // NOP
299        }
300      }
301
302      m_lastMode = mode;
303    }
304
305    // Call the appropriate function depending upon the current robot mode
306    DriverStationJNI.observeUserProgram(m_word.getNative());
307    switch (mode) {
308      case UNKNOWN -> {
309        disabledPeriodic();
310        m_watchdog.addEpoch("disabledPeriodic()");
311      }
312      case AUTONOMOUS -> {
313        autonomousPeriodic();
314        m_watchdog.addEpoch("autonomousPeriodic()");
315      }
316      case TELEOPERATED -> {
317        teleopPeriodic();
318        m_watchdog.addEpoch("teleopPeriodic()");
319      }
320      case TEST -> {
321        testPeriodic();
322        m_watchdog.addEpoch("testPeriodic()");
323      }
324      default -> {
325        // NOP
326      }
327    }
328
329    robotPeriodic();
330    m_watchdog.addEpoch("robotPeriodic()");
331
332    SmartDashboard.updateValues();
333    m_watchdog.addEpoch("SmartDashboard.updateValues()");
334
335    if (isSimulation()) {
336      HAL.simPeriodicBefore();
337      simulationPeriodic();
338      HAL.simPeriodicAfter();
339      m_watchdog.addEpoch("simulationPeriodic()");
340    }
341
342    m_watchdog.disable();
343
344    // Flush NetworkTables
345    if (m_ntFlushEnabled) {
346      NetworkTableInstance.getDefault().flushLocal();
347    }
348
349    // Warn on loop time overruns
350    if (m_watchdog.isExpired()) {
351      m_watchdog.printEpochs();
352    }
353  }
354
355  /** Prints list of epochs added so far and their times. */
356  public void printWatchdogEpochs() {
357    m_watchdog.printEpochs();
358  }
359
360  private void printLoopOverrunMessage() {
361    DriverStation.reportWarning("Loop time of " + m_period + "s overrun\n", false);
362  }
363}