WPILibC++ 2024.3.2
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 * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
67 * indicators will be off until RobotInit() exits. Code in RobotInit() that
68 * waits for enable will cause the robot to never indicate that the code is
69 * ready, causing the robot to be bypassed in a match.
70 */
71 virtual void RobotInit();
72
73 /**
74 * Code that needs to know the DS state should go here.
75 *
76 * Users should override this method for initialization that needs to occur
77 * after the DS is connected, such as needing the alliance information.
78 */
79 virtual void DriverStationConnected();
80
81 /**
82 * Robot-wide simulation initialization code should go here.
83 *
84 * Users should override this method for default Robot-wide simulation
85 * related initialization which will be called when the robot is first
86 * started. It will be called exactly one time after RobotInit is called
87 * only when the robot is in simulation.
88 */
89 virtual void SimulationInit();
90
91 /**
92 * Initialization code for disabled mode should go here.
93 *
94 * Users should override this method for initialization code which will be
95 * called each time
96 * the robot enters disabled mode.
97 */
98 virtual void DisabledInit();
99
100 /**
101 * Initialization code for autonomous mode should go here.
102 *
103 * Users should override this method for initialization code which will be
104 * called each time the robot enters autonomous mode.
105 */
106 virtual void AutonomousInit();
107
108 /**
109 * Initialization code for teleop mode should go here.
110 *
111 * Users should override this method for initialization code which will be
112 * called each time the robot enters teleop mode.
113 */
114 virtual void TeleopInit();
115
116 /**
117 * Initialization code for test mode should go here.
118 *
119 * Users should override this method for initialization code which will be
120 * called each time the robot enters test mode.
121 */
122 virtual void TestInit();
123
124 /**
125 * Periodic code for all modes should go here.
126 *
127 * This function is called each time a new packet is received from the driver
128 * station.
129 */
130 virtual void RobotPeriodic();
131
132 /**
133 * Periodic simulation code should go here.
134 *
135 * This function is called in a simulated robot after user code executes.
136 */
137 virtual void SimulationPeriodic();
138
139 /**
140 * Periodic code for disabled mode should go here.
141 *
142 * Users should override this method for code which will be called each time a
143 * new packet is received from the driver station and the robot is in disabled
144 * mode.
145 */
146 virtual void DisabledPeriodic();
147
148 /**
149 * Periodic code for autonomous mode should go here.
150 *
151 * Users should override this method for code which will be called each time a
152 * new packet is received from the driver station and the robot is in
153 * autonomous mode.
154 */
155 virtual void AutonomousPeriodic();
156
157 /**
158 * Periodic code for teleop mode should go here.
159 *
160 * Users should override this method for code which will be called each time a
161 * new packet is received from the driver station and the robot is in teleop
162 * mode.
163 */
164 virtual void TeleopPeriodic();
165
166 /**
167 * Periodic code for test mode should go here.
168 *
169 * Users should override this method for code which will be called each time a
170 * new packet is received from the driver station and the robot is in test
171 * mode.
172 */
173 virtual void TestPeriodic();
174
175 /**
176 * Exit code for disabled mode should go here.
177 *
178 * Users should override this method for code which will be called each time
179 * the robot exits disabled mode.
180 */
181 virtual void DisabledExit();
182
183 /**
184 * Exit code for autonomous mode should go here.
185 *
186 * Users should override this method for code which will be called each time
187 * the robot exits autonomous mode.
188 */
189 virtual void AutonomousExit();
190
191 /**
192 * Exit code for teleop mode should go here.
193 *
194 * Users should override this method for code which will be called each time
195 * the robot exits teleop mode.
196 */
197 virtual void TeleopExit();
198
199 /**
200 * Exit code for test mode should go here.
201 *
202 * Users should override this method for code which will be called each time
203 * the robot exits test mode.
204 */
205 virtual void TestExit();
206
207 /**
208 * Enables or disables flushing NetworkTables every loop iteration.
209 * By default, this is enabled.
210 *
211 * @param enabled True to enable, false to disable
212 */
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 * Constructor for IterativeRobotBase.
235 *
236 * @param period Period.
237 */
238 explicit IterativeRobotBase(units::second_t period);
239
240 ~IterativeRobotBase() override = default;
241
242 protected:
245
246 /**
247 * Loop function.
248 */
249 void LoopFunc();
250
251 private:
252 enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
253
254 Mode m_lastMode = Mode::kNone;
255 units::second_t m_period;
256 Watchdog m_watchdog;
257 bool m_ntFlushEnabled = true;
258 bool m_lwEnabledInTest = false;
259 bool m_calledDsConnected = false;
260
261 void PrintLoopOverrunMessage();
262};
263
264} // 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.
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:127
A class that's a wrapper around a watchdog timer.
Definition: Watchdog.h:26
Definition: AprilTagPoseEstimator.h:15