WPILibC++ 2027.0.0-alpha-3
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 * DriverStationConnected() -- provide for initialization the first time the DS
25 * is connected
26 *
27 * Init() functions -- each of the following functions is called once when the
28 * appropriate mode is entered:
29 *
30 * \li DisabledInit() -- called each and every time disabled is entered from
31 * another mode
32 * \li AutonomousInit() -- called each and every time autonomous is entered from
33 * another mode
34 * \li TeleopInit() -- called each and every time teleop is entered from another
35 * mode
36 * \li TestInit() -- called each and every time test is entered from another
37 * mode
38 *
39 * Periodic() functions -- each of these functions is called on an interval:
40 *
41 * \li RobotPeriodic()
42 * \li DisabledPeriodic()
43 * \li AutonomousPeriodic()
44 * \li TeleopPeriodic()
45 * \li TestPeriodic()
46 *
47 * Exit() functions -- each of the following functions is called once when the
48 * appropriate mode is exited:
49 *
50 * \li DisabledExit() -- called each and every time disabled is exited
51 * \li AutonomousExit() -- called each and every time autonomous is exited
52 * \li TeleopExit() -- called each and every time teleop is exited
53 * \li TestExit() -- called each and every time test is exited
54 */
56 public:
57 /**
58 * Code that needs to know the DS state should go here.
59 *
60 * Users should override this method for initialization that needs to occur
61 * after the DS is connected, such as needing the alliance information.
62 */
63 virtual void DriverStationConnected();
64
65 /**
66 * Robot-wide simulation initialization code should go here.
67 *
68 * Users should override this method for default Robot-wide simulation
69 * related initialization which will be called when the robot is first
70 * started. It will be called exactly one time after the robot class
71 * constructor is called only when the robot is in simulation.
72 */
73 virtual void SimulationInit();
74
75 /**
76 * Initialization code for disabled mode should go here.
77 *
78 * Users should override this method for initialization code which will be
79 * called each time
80 * the robot enters disabled mode.
81 */
82 virtual void DisabledInit();
83
84 /**
85 * Initialization code for autonomous mode should go here.
86 *
87 * Users should override this method for initialization code which will be
88 * called each time the robot enters autonomous mode.
89 */
90 virtual void AutonomousInit();
91
92 /**
93 * Initialization code for teleop mode should go here.
94 *
95 * Users should override this method for initialization code which will be
96 * called each time the robot enters teleop mode.
97 */
98 virtual void TeleopInit();
99
100 /**
101 * Initialization code for test mode should go here.
102 *
103 * Users should override this method for initialization code which will be
104 * called each time the robot enters test mode.
105 */
106 virtual void TestInit();
107
108 /**
109 * Periodic code for all modes should go here.
110 *
111 * This function is called each time a new packet is received from the driver
112 * station.
113 */
114 virtual void RobotPeriodic();
115
116 /**
117 * Periodic simulation code should go here.
118 *
119 * This function is called in a simulated robot after user code executes.
120 */
121 virtual void SimulationPeriodic();
122
123 /**
124 * Periodic code for disabled mode should go here.
125 *
126 * Users should override this method for code which will be called each time a
127 * new packet is received from the driver station and the robot is in disabled
128 * mode.
129 */
130 virtual void DisabledPeriodic();
131
132 /**
133 * Periodic code for autonomous mode should go here.
134 *
135 * Users should override this method for code which will be called each time a
136 * new packet is received from the driver station and the robot is in
137 * autonomous mode.
138 */
139 virtual void AutonomousPeriodic();
140
141 /**
142 * Periodic code for teleop mode should go here.
143 *
144 * Users should override this method for code which will be called each time a
145 * new packet is received from the driver station and the robot is in teleop
146 * mode.
147 */
148 virtual void TeleopPeriodic();
149
150 /**
151 * Periodic code for test mode should go here.
152 *
153 * Users should override this method for code which will be called each time a
154 * new packet is received from the driver station and the robot is in test
155 * mode.
156 */
157 virtual void TestPeriodic();
158
159 /**
160 * Exit code for disabled mode should go here.
161 *
162 * Users should override this method for code which will be called each time
163 * the robot exits disabled mode.
164 */
165 virtual void DisabledExit();
166
167 /**
168 * Exit code for autonomous mode should go here.
169 *
170 * Users should override this method for code which will be called each time
171 * the robot exits autonomous mode.
172 */
173 virtual void AutonomousExit();
174
175 /**
176 * Exit code for teleop mode should go here.
177 *
178 * Users should override this method for code which will be called each time
179 * the robot exits teleop mode.
180 */
181 virtual void TeleopExit();
182
183 /**
184 * Exit code for test mode should go here.
185 *
186 * Users should override this method for code which will be called each time
187 * the robot exits test mode.
188 */
189 virtual void TestExit();
190
191 /**
192 * Enables or disables flushing NetworkTables every loop iteration.
193 * By default, this is enabled.
194 *
195 * @param enabled True to enable, false to disable
196 * @deprecated Deprecated without replacement.
197 */
198 [[deprecated("Deprecated without replacement.")]]
200
201 /**
202 * Gets time period between calls to Periodic() functions.
203 */
204 units::second_t GetPeriod() const;
205
206 /**
207 * Prints list of epochs added so far and their times.
208 */
210
211 /**
212 * Constructor for IterativeRobotBase.
213 *
214 * @param period Period.
215 */
216 explicit IterativeRobotBase(units::second_t period);
217
218 ~IterativeRobotBase() override = default;
219
220 protected:
223
224 /**
225 * Loop function.
226 */
227 void LoopFunc();
228
229 private:
230 enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
231
232 Mode m_lastMode = Mode::kNone;
233 units::second_t m_period;
234 Watchdog m_watchdog;
235 bool m_ntFlushEnabled = true;
236 bool m_calledDsConnected = false;
237
238 void PrintLoopOverrunMessage();
239};
240
241} // namespace frc
IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase cla...
Definition IterativeRobotBase.h:55
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.
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.
~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 SystemServer.h:9