WPILibC++ 2025.3.1
Loading...
Searching...
No Matches
IterativeRobotBase.h
Go to the documentation of this file.
1// Copyright (c) FIRST and other WPILib contributors.
2// Open Source Software; you can modify and/or share it under the terms of
3// the WPILib BSD license file in the root directory of this project.
4
5#pragma once
6
7#include <units/time.h>
8
9#include "frc/RobotBase.h"
10#include "frc/Watchdog.h"
11
12namespace frc {
13
14/**
15 * IterativeRobotBase implements a specific type of robot program framework,
16 * extending the RobotBase class.
17 *
18 * The IterativeRobotBase class does not implement StartCompetition(), so it
19 * should not be used by teams directly.
20 *
21 * This class provides the following functions which are called by the main
22 * loop, StartCompetition(), at the appropriate times:
23 *
24 * RobotInit() -- provide for initialization at robot power-on
25 *
26 * DriverStationConnected() -- provide for initialization the first time the DS
27 * is connected
28 *
29 * Init() functions -- each of the following functions is called once when the
30 * appropriate mode is entered:
31 *
32 * \li DisabledInit() -- called each and every time disabled is entered from
33 * another mode
34 * \li AutonomousInit() -- called each and every time autonomous is entered from
35 * another mode
36 * \li TeleopInit() -- called each and every time teleop is entered from another
37 * mode
38 * \li TestInit() -- called each and every time test is entered from another
39 * mode
40 *
41 * Periodic() functions -- each of these functions is called on an interval:
42 *
43 * \li RobotPeriodic()
44 * \li DisabledPeriodic()
45 * \li AutonomousPeriodic()
46 * \li TeleopPeriodic()
47 * \li TestPeriodic()
48 *
49 * Exit() functions -- each of the following functions is called once when the
50 * appropriate mode is exited:
51 *
52 * \li DisabledExit() -- called each and every time disabled is exited
53 * \li AutonomousExit() -- called each and every time autonomous is exited
54 * \li TeleopExit() -- called each and every time teleop is exited
55 * \li TestExit() -- called each and every time test is exited
56 */
58 public:
59 /**
60 * Robot-wide initialization code should go here.
61 *
62 * Users should override this method for default Robot-wide initialization
63 * which will be called when the robot is first powered on. It will be called
64 * exactly one time.
65 *
66 * Note: This method is functionally identical to the class constructor so
67 * that should be used instead.
68 */
69 virtual void RobotInit();
70
71 /**
72 * Code that needs to know the DS state should go here.
73 *
74 * Users should override this method for initialization that needs to occur
75 * after the DS is connected, such as needing the alliance information.
76 */
77 virtual void DriverStationConnected();
78
79 /**
80 * Robot-wide simulation initialization code should go here.
81 *
82 * Users should override this method for default Robot-wide simulation
83 * related initialization which will be called when the robot is first
84 * started. It will be called exactly one time after RobotInit is called
85 * only when the robot is in simulation.
86 */
87 virtual void SimulationInit();
88
89 /**
90 * Initialization code for disabled mode should go here.
91 *
92 * Users should override this method for initialization code which will be
93 * called each time
94 * the robot enters disabled mode.
95 */
96 virtual void DisabledInit();
97
98 /**
99 * Initialization code for autonomous mode should go here.
100 *
101 * Users should override this method for initialization code which will be
102 * called each time the robot enters autonomous mode.
103 */
104 virtual void AutonomousInit();
105
106 /**
107 * Initialization code for teleop mode should go here.
108 *
109 * Users should override this method for initialization code which will be
110 * called each time the robot enters teleop mode.
111 */
112 virtual void TeleopInit();
113
114 /**
115 * Initialization code for test mode should go here.
116 *
117 * Users should override this method for initialization code which will be
118 * called each time the robot enters test mode.
119 */
120 virtual void TestInit();
121
122 /**
123 * Periodic code for all modes should go here.
124 *
125 * This function is called each time a new packet is received from the driver
126 * station.
127 */
128 virtual void RobotPeriodic();
129
130 /**
131 * Periodic simulation code should go here.
132 *
133 * This function is called in a simulated robot after user code executes.
134 */
135 virtual void SimulationPeriodic();
136
137 /**
138 * Periodic code for disabled mode should go here.
139 *
140 * Users should override this method for code which will be called each time a
141 * new packet is received from the driver station and the robot is in disabled
142 * mode.
143 */
144 virtual void DisabledPeriodic();
145
146 /**
147 * Periodic code for autonomous mode should go here.
148 *
149 * Users should override this method for code which will be called each time a
150 * new packet is received from the driver station and the robot is in
151 * autonomous mode.
152 */
153 virtual void AutonomousPeriodic();
154
155 /**
156 * Periodic code for teleop mode should go here.
157 *
158 * Users should override this method for code which will be called each time a
159 * new packet is received from the driver station and the robot is in teleop
160 * mode.
161 */
162 virtual void TeleopPeriodic();
163
164 /**
165 * Periodic code for test mode should go here.
166 *
167 * Users should override this method for code which will be called each time a
168 * new packet is received from the driver station and the robot is in test
169 * mode.
170 */
171 virtual void TestPeriodic();
172
173 /**
174 * Exit code for disabled mode should go here.
175 *
176 * Users should override this method for code which will be called each time
177 * the robot exits disabled mode.
178 */
179 virtual void DisabledExit();
180
181 /**
182 * Exit code for autonomous mode should go here.
183 *
184 * Users should override this method for code which will be called each time
185 * the robot exits autonomous mode.
186 */
187 virtual void AutonomousExit();
188
189 /**
190 * Exit code for teleop mode should go here.
191 *
192 * Users should override this method for code which will be called each time
193 * the robot exits teleop mode.
194 */
195 virtual void TeleopExit();
196
197 /**
198 * Exit code for test mode should go here.
199 *
200 * Users should override this method for code which will be called each time
201 * the robot exits test mode.
202 */
203 virtual void TestExit();
204
205 /**
206 * Enables or disables flushing NetworkTables every loop iteration.
207 * By default, this is enabled.
208 *
209 * @param enabled True to enable, false to disable
210 * @deprecated Deprecated without replacement.
211 */
212 [[deprecated("Deprecated without replacement.")]]
214
215 /**
216 * Sets whether LiveWindow operation is enabled during test mode.
217 *
218 * @param testLW True to enable, false to disable. Defaults to false.
219 * @throws if called in test mode.
220 */
221 void EnableLiveWindowInTest(bool testLW);
222
223 /**
224 * Whether LiveWindow operation is enabled during test mode.
225 */
227
228 /**
229 * Gets time period between calls to Periodic() functions.
230 */
231 units::second_t GetPeriod() const;
232
233 /**
234 * Prints list of epochs added so far and their times.
235 */
237
238 /**
239 * Constructor for IterativeRobotBase.
240 *
241 * @param period Period.
242 */
243 explicit IterativeRobotBase(units::second_t period);
244
245 ~IterativeRobotBase() override = default;
246
247 protected:
250
251 /**
252 * Loop function.
253 */
254 void LoopFunc();
255
256 private:
257 enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
258
259 Mode m_lastMode = Mode::kNone;
260 units::second_t m_period;
261 Watchdog m_watchdog;
262 bool m_ntFlushEnabled = true;
263 bool m_lwEnabledInTest = false;
264 bool m_calledDsConnected = false;
265
266 void PrintLoopOverrunMessage();
267};
268
269} // namespace frc
IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase cla...
Definition IterativeRobotBase.h:57
virtual void RobotInit()
Robot-wide initialization code should go here.
virtual void TestInit()
Initialization code for test mode should go here.
virtual void RobotPeriodic()
Periodic code for all modes should go here.
virtual void TeleopPeriodic()
Periodic code for teleop mode should go here.
virtual void TestExit()
Exit code for test mode should go here.
virtual void TestPeriodic()
Periodic code for test mode should go here.
virtual void TeleopInit()
Initialization code for teleop mode should go here.
virtual void SimulationPeriodic()
Periodic simulation code should go here.
void EnableLiveWindowInTest(bool testLW)
Sets whether LiveWindow operation is enabled during test mode.
IterativeRobotBase & operator=(IterativeRobotBase &&)=default
virtual void DriverStationConnected()
Code that needs to know the DS state should go here.
virtual void DisabledExit()
Exit code for disabled mode should go here.
void PrintWatchdogEpochs()
Prints list of epochs added so far and their times.
virtual void TeleopExit()
Exit code for teleop mode should go here.
void LoopFunc()
Loop function.
virtual void SimulationInit()
Robot-wide simulation initialization code should go here.
virtual void DisabledPeriodic()
Periodic code for disabled mode should go here.
virtual void DisabledInit()
Initialization code for disabled mode should go here.
virtual void AutonomousInit()
Initialization code for autonomous mode should go here.
bool IsLiveWindowEnabledInTest()
Whether LiveWindow operation is enabled during test mode.
~IterativeRobotBase() override=default
IterativeRobotBase(IterativeRobotBase &&)=default
virtual void AutonomousExit()
Exit code for autonomous mode should go here.
units::second_t GetPeriod() const
Gets time period between calls to Periodic() functions.
virtual void AutonomousPeriodic()
Periodic code for autonomous mode should go here.
void SetNetworkTablesFlushEnabled(bool enabled)
Enables or disables flushing NetworkTables every loop iteration.
IterativeRobotBase(units::second_t period)
Constructor for IterativeRobotBase.
Implement a Robot Program framework.
Definition RobotBase.h:145
A class that's a wrapper around a watchdog timer.
Definition Watchdog.h:26
Definition CAN.h:11