252 enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
254 Mode m_lastMode = Mode::kNone;
255 units::second_t m_period;
257 bool m_ntFlushEnabled =
true;
258 bool m_lwEnabledInTest =
false;
259 bool m_calledDsConnected =
false;
261 void PrintLoopOverrunMessage();
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