WPILibC++ 2023.4.3
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 * Init() functions -- each of the following functions is called once when the
27 * appropriate mode is entered:
28 *
29 * \li DisabledInit() -- called each and every time disabled is entered from
30 * another mode
31 * \li AutonomousInit() -- called each and every time autonomous is entered from
32 * another mode
33 * \li TeleopInit() -- called each and every time teleop is entered from another
34 * mode
35 * \li TestInit() -- called each and every time test is entered from another
36 * mode
37 *
38 * Periodic() functions -- each of these functions is called on an interval:
39 *
40 * \li RobotPeriodic()
41 * \li DisabledPeriodic()
42 * \li AutonomousPeriodic()
43 * \li TeleopPeriodic()
44 * \li TestPeriodic()
45 *
46 * Exit() functions -- each of the following functions is called once when the
47 * appropriate mode is exited:
48 *
49 * \li DisabledExit() -- called each and every time disabled is exited
50 * \li AutonomousExit() -- called each and every time autonomous is exited
51 * \li TeleopExit() -- called each and every time teleop is exited
52 * \li TestExit() -- called each and every time test is exited
53 */
55 public:
56 /**
57 * Robot-wide initialization code should go here.
58 *
59 * Users should override this method for default Robot-wide initialization
60 * which will be called when the robot is first powered on. It will be called
61 * exactly one time.
62 *
63 * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
64 * indicators will be off until RobotInit() exits. Code in RobotInit() that
65 * waits for enable will cause the robot to never indicate that the code is
66 * ready, causing the robot to be bypassed in a match.
67 */
68 virtual void RobotInit();
69
70 /**
71 * Robot-wide simulation initialization code should go here.
72 *
73 * Users should override this method for default Robot-wide simulation
74 * related initialization which will be called when the robot is first
75 * started. It will be called exactly one time after RobotInit is called
76 * only when the robot is in simulation.
77 */
78 virtual void SimulationInit();
79
80 /**
81 * Initialization code for disabled mode should go here.
82 *
83 * Users should override this method for initialization code which will be
84 * called each time
85 * the robot enters disabled mode.
86 */
87 virtual void DisabledInit();
88
89 /**
90 * Initialization code for autonomous mode should go here.
91 *
92 * Users should override this method for initialization code which will be
93 * called each time the robot enters autonomous mode.
94 */
95 virtual void AutonomousInit();
96
97 /**
98 * Initialization code for teleop mode should go here.
99 *
100 * Users should override this method for initialization code which will be
101 * called each time the robot enters teleop mode.
102 */
103 virtual void TeleopInit();
104
105 /**
106 * Initialization code for test mode should go here.
107 *
108 * Users should override this method for initialization code which will be
109 * called each time the robot enters test mode.
110 */
111 virtual void TestInit();
112
113 /**
114 * Periodic code for all modes should go here.
115 *
116 * This function is called each time a new packet is received from the driver
117 * station.
118 */
119 virtual void RobotPeriodic();
120
121 /**
122 * Periodic simulation code should go here.
123 *
124 * This function is called in a simulated robot after user code executes.
125 */
126 virtual void SimulationPeriodic();
127
128 /**
129 * Periodic code for disabled mode should go here.
130 *
131 * Users should override this method for code which will be called each time a
132 * new packet is received from the driver station and the robot is in disabled
133 * mode.
134 */
135 virtual void DisabledPeriodic();
136
137 /**
138 * Periodic code for autonomous 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
142 * autonomous mode.
143 */
144 virtual void AutonomousPeriodic();
145
146 /**
147 * Periodic code for teleop 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 teleop
151 * mode.
152 */
153 virtual void TeleopPeriodic();
154
155 /**
156 * Periodic code for test 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 test
160 * mode.
161 */
162 virtual void TestPeriodic();
163
164 /**
165 * Exit code for disabled mode should go here.
166 *
167 * Users should override this method for code which will be called each time
168 * the robot exits disabled mode.
169 */
170 virtual void DisabledExit();
171
172 /**
173 * Exit code for autonomous mode should go here.
174 *
175 * Users should override this method for code which will be called each time
176 * the robot exits autonomous mode.
177 */
178 virtual void AutonomousExit();
179
180 /**
181 * Exit code for teleop mode should go here.
182 *
183 * Users should override this method for code which will be called each time
184 * the robot exits teleop mode.
185 */
186 virtual void TeleopExit();
187
188 /**
189 * Exit code for test mode should go here.
190 *
191 * Users should override this method for code which will be called each time
192 * the robot exits test mode.
193 */
194 virtual void TestExit();
195
196 /**
197 * Enables or disables flushing NetworkTables every loop iteration.
198 * By default, this is enabled.
199 *
200 * @param enabled True to enable, false to disable
201 */
203
204 /**
205 * Sets whether LiveWindow operation is enabled during test mode.
206 *
207 * @param testLW True to enable, false to disable. Defaults to true.
208 * @throws if called in test mode.
209 */
210 void EnableLiveWindowInTest(bool testLW);
211
212 /**
213 * Whether LiveWindow operation is enabled during test mode.
214 */
216
217 /**
218 * Gets time period between calls to Periodic() functions.
219 */
220 units::second_t GetPeriod() const;
221
222 /**
223 * Constructor for IterativeRobotBase.
224 *
225 * @param period Period.
226 */
227 explicit IterativeRobotBase(units::second_t period);
228
229 ~IterativeRobotBase() override = default;
230
231 protected:
234
235 void LoopFunc();
236
237 private:
238 enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
239
240 Mode m_lastMode = Mode::kNone;
241 units::second_t m_period;
242 Watchdog m_watchdog;
243 bool m_ntFlushEnabled = true;
244 bool m_lwEnabledInTest = true;
245
246 void PrintLoopOverrunMessage();
247};
248
249} // namespace frc
IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase cla...
Definition: IterativeRobotBase.h:54
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 DisabledExit()
Exit code for disabled mode should go here.
virtual void TeleopExit()
Exit code for teleop mode should go here.
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: AprilTagFieldLayout.h:22