WPILibC++ 2027.0.0-alpha-4
Loading...
Searching...
No Matches
IterativeRobotBase.hpp
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
9#include "wpi/units/time.hpp"
10
11namespace wpi {
12
13/**
14 * IterativeRobotBase implements a specific type of robot program framework,
15 * extending the RobotBase class.
16 *
17 * The IterativeRobotBase class does not implement StartCompetition(), so it
18 * should not be used by teams directly.
19 *
20 * This class provides the following functions which are called by the main
21 * loop, StartCompetition(), at the appropriate times:
22 *
23 * DriverStationConnected() -- provide for initialization the first time the DS
24 * is connected
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 * Code that needs to know the DS state should go here.
58 *
59 * Users should override this method for initialization that needs to occur
60 * after the DS is connected, such as needing the alliance information.
61 */
62 virtual void DriverStationConnected();
63
64 /**
65 * Robot-wide simulation initialization code should go here.
66 *
67 * Users should override this method for default Robot-wide simulation
68 * related initialization which will be called when the robot is first
69 * started. It will be called exactly one time after the robot class
70 * constructor is called only when the robot is in simulation.
71 */
72 virtual void SimulationInit();
73
74 /**
75 * Initialization code for disabled mode should go here.
76 *
77 * Users should override this method for initialization code which will be
78 * called each time
79 * the robot enters disabled mode.
80 */
81 virtual void DisabledInit();
82
83 /**
84 * Initialization code for autonomous mode should go here.
85 *
86 * Users should override this method for initialization code which will be
87 * called each time the robot enters autonomous mode.
88 */
89 virtual void AutonomousInit();
90
91 /**
92 * Initialization code for teleop mode should go here.
93 *
94 * Users should override this method for initialization code which will be
95 * called each time the robot enters teleop mode.
96 */
97 virtual void TeleopInit();
98
99 /**
100 * Initialization code for test mode should go here.
101 *
102 * Users should override this method for initialization code which will be
103 * called each time the robot enters test mode.
104 */
105 virtual void TestInit();
106
107 /**
108 * Periodic code for all modes should go here.
109 *
110 * This function is called each time a new packet is received from the driver
111 * station.
112 */
113 virtual void RobotPeriodic();
114
115 /**
116 * Periodic simulation code should go here.
117 *
118 * This function is called in a simulated robot after user code executes.
119 */
120 virtual void SimulationPeriodic();
121
122 /**
123 * Periodic code for disabled mode should go here.
124 *
125 * Users should override this method for code which will be called each time a
126 * new packet is received from the driver station and the robot is in disabled
127 * mode.
128 */
129 virtual void DisabledPeriodic();
130
131 /**
132 * Periodic code for autonomous mode should go here.
133 *
134 * Users should override this method for code which will be called each time a
135 * new packet is received from the driver station and the robot is in
136 * autonomous mode.
137 */
138 virtual void AutonomousPeriodic();
139
140 /**
141 * Periodic code for teleop mode should go here.
142 *
143 * Users should override this method for code which will be called each time a
144 * new packet is received from the driver station and the robot is in teleop
145 * mode.
146 */
147 virtual void TeleopPeriodic();
148
149 /**
150 * Periodic code for test mode should go here.
151 *
152 * Users should override this method for code which will be called each time a
153 * new packet is received from the driver station and the robot is in test
154 * mode.
155 */
156 virtual void TestPeriodic();
157
158 /**
159 * Exit code for disabled mode should go here.
160 *
161 * Users should override this method for code which will be called each time
162 * the robot exits disabled mode.
163 */
164 virtual void DisabledExit();
165
166 /**
167 * Exit code for autonomous mode should go here.
168 *
169 * Users should override this method for code which will be called each time
170 * the robot exits autonomous mode.
171 */
172 virtual void AutonomousExit();
173
174 /**
175 * Exit code for teleop mode should go here.
176 *
177 * Users should override this method for code which will be called each time
178 * the robot exits teleop mode.
179 */
180 virtual void TeleopExit();
181
182 /**
183 * Exit code for test mode should go here.
184 *
185 * Users should override this method for code which will be called each time
186 * the robot exits test mode.
187 */
188 virtual void TestExit();
189
190 /**
191 * Enables or disables flushing NetworkTables every loop iteration.
192 * By default, this is enabled.
193 *
194 * @param enabled True to enable, false to disable
195 * @deprecated Deprecated without replacement.
196 */
197 [[deprecated("Deprecated without replacement.")]]
199
200 /**
201 * Gets time period between calls to Periodic() functions.
202 */
203 wpi::units::second_t GetPeriod() const;
204
205 /**
206 * Prints list of epochs added so far and their times.
207 */
209
210 /**
211 * Constructor for IterativeRobotBase.
212 *
213 * @param period Period.
214 */
215 explicit IterativeRobotBase(wpi::units::second_t period);
216
217 ~IterativeRobotBase() override = default;
218
219 protected:
222
223 /**
224 * Loop function.
225 */
226 void LoopFunc();
227
228 private:
229 int m_lastMode = -1;
230 wpi::units::second_t m_period;
231 Watchdog m_watchdog;
232 bool m_ntFlushEnabled = true;
233 bool m_calledDsConnected = false;
234
235 void PrintLoopOverrunMessage();
236};
237
238} // namespace wpi
virtual void TestPeriodic()
Periodic code for test mode should go here.
virtual void SimulationPeriodic()
Periodic simulation code should go here.
virtual void TeleopExit()
Exit code for teleop mode should go here.
virtual void DisabledInit()
Initialization code for disabled 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.
void PrintWatchdogEpochs()
Prints list of epochs added so far and their times.
IterativeRobotBase(IterativeRobotBase &&)=default
virtual void RobotPeriodic()
Periodic code for all modes should go here.
void LoopFunc()
Loop function.
~IterativeRobotBase() override=default
virtual void AutonomousExit()
Exit code for autonomous mode should go here.
void SetNetworkTablesFlushEnabled(bool enabled)
Enables or disables flushing NetworkTables every loop iteration.
virtual void DriverStationConnected()
Code that needs to know the DS state should go here.
virtual void AutonomousInit()
Initialization code for autonomous mode should go here.
IterativeRobotBase(wpi::units::second_t period)
Constructor for IterativeRobotBase.
virtual void TestExit()
Exit code for test mode should go here.
IterativeRobotBase & operator=(IterativeRobotBase &&)=default
virtual void AutonomousPeriodic()
Periodic code for autonomous mode should go here.
virtual void DisabledExit()
Exit code for disabled mode should go here.
virtual void TestInit()
Initialization code for test mode should go here.
virtual void TeleopInit()
Initialization code for teleop mode should go here.
virtual void TeleopPeriodic()
Periodic code for teleop mode should go here.
wpi::units::second_t GetPeriod() const
Gets time period between calls to Periodic() functions.
RobotBase()
Constructor for a generic robot program.
A class that's a wrapper around a watchdog timer.
Definition Watchdog.hpp:25
Definition CvSource.hpp:15