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