IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class.
More...
#include <frc/IterativeRobotBase.h>
IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class.
The IterativeRobotBase class does not implement StartCompetition(), so it should not be used by teams directly.
This class provides the following functions which are called by the main loop, StartCompetition(), at the appropriate times:
RobotInit() – provide for initialization at robot power-on
DriverStationConnected() – provide for initialization the first time the DS is connected
Init() functions – each of the following functions is called once when the appropriate mode is entered:
- DisabledInit() – called each and every time disabled is entered from another mode
- AutonomousInit() – called each and every time autonomous is entered from another mode
- TeleopInit() – called each and every time teleop is entered from another mode
- TestInit() – called each and every time test is entered from another mode
Periodic() functions – each of these functions is called on an interval:
Exit() functions – each of the following functions is called once when the appropriate mode is exited:
◆ IterativeRobotBase() [1/2]
frc::IterativeRobotBase::IterativeRobotBase |
( |
units::second_t |
period | ) |
|
|
explicit |
◆ ~IterativeRobotBase()
frc::IterativeRobotBase::~IterativeRobotBase |
( |
| ) |
|
|
overridedefault |
◆ IterativeRobotBase() [2/2]
◆ AutonomousExit()
virtual void frc::IterativeRobotBase::AutonomousExit |
( |
| ) |
|
|
virtual |
Exit code for autonomous mode should go here.
Users should override this method for code which will be called each time the robot exits autonomous mode.
◆ AutonomousInit()
virtual void frc::IterativeRobotBase::AutonomousInit |
( |
| ) |
|
|
virtual |
Initialization code for autonomous mode should go here.
Users should override this method for initialization code which will be called each time the robot enters autonomous mode.
◆ AutonomousPeriodic()
virtual void frc::IterativeRobotBase::AutonomousPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for autonomous mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in autonomous mode.
◆ DisabledExit()
virtual void frc::IterativeRobotBase::DisabledExit |
( |
| ) |
|
|
virtual |
Exit code for disabled mode should go here.
Users should override this method for code which will be called each time the robot exits disabled mode.
◆ DisabledInit()
virtual void frc::IterativeRobotBase::DisabledInit |
( |
| ) |
|
|
virtual |
Initialization code for disabled mode should go here.
Users should override this method for initialization code which will be called each time the robot enters disabled mode.
◆ DisabledPeriodic()
virtual void frc::IterativeRobotBase::DisabledPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for disabled mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in disabled mode.
◆ DriverStationConnected()
virtual void frc::IterativeRobotBase::DriverStationConnected |
( |
| ) |
|
|
virtual |
Code that needs to know the DS state should go here.
Users should override this method for initialization that needs to occur after the DS is connected, such as needing the alliance information.
◆ EnableLiveWindowInTest()
void frc::IterativeRobotBase::EnableLiveWindowInTest |
( |
bool |
testLW | ) |
|
Sets whether LiveWindow operation is enabled during test mode.
- Parameters
-
testLW | True to enable, false to disable. Defaults to true. |
- Exceptions
-
◆ GetPeriod()
units::second_t frc::IterativeRobotBase::GetPeriod |
( |
| ) |
const |
Gets time period between calls to Periodic() functions.
◆ IsLiveWindowEnabledInTest()
bool frc::IterativeRobotBase::IsLiveWindowEnabledInTest |
( |
| ) |
|
Whether LiveWindow operation is enabled during test mode.
◆ LoopFunc()
void frc::IterativeRobotBase::LoopFunc |
( |
| ) |
|
|
protected |
◆ operator=()
◆ RobotInit()
virtual void frc::IterativeRobotBase::RobotInit |
( |
| ) |
|
|
virtual |
Robot-wide initialization code should go here.
Users should override this method for default Robot-wide initialization which will be called when the robot is first powered on. It will be called exactly one time.
Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to never indicate that the code is ready, causing the robot to be bypassed in a match.
◆ RobotPeriodic()
virtual void frc::IterativeRobotBase::RobotPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for all modes should go here.
This function is called each time a new packet is received from the driver station.
◆ SetNetworkTablesFlushEnabled()
void frc::IterativeRobotBase::SetNetworkTablesFlushEnabled |
( |
bool |
enabled | ) |
|
Enables or disables flushing NetworkTables every loop iteration.
By default, this is enabled.
- Parameters
-
enabled | True to enable, false to disable |
◆ SimulationInit()
virtual void frc::IterativeRobotBase::SimulationInit |
( |
| ) |
|
|
virtual |
Robot-wide simulation initialization code should go here.
Users should override this method for default Robot-wide simulation related initialization which will be called when the robot is first started. It will be called exactly one time after RobotInit is called only when the robot is in simulation.
◆ SimulationPeriodic()
virtual void frc::IterativeRobotBase::SimulationPeriodic |
( |
| ) |
|
|
virtual |
Periodic simulation code should go here.
This function is called in a simulated robot after user code executes.
◆ TeleopExit()
virtual void frc::IterativeRobotBase::TeleopExit |
( |
| ) |
|
|
virtual |
Exit code for teleop mode should go here.
Users should override this method for code which will be called each time the robot exits teleop mode.
◆ TeleopInit()
virtual void frc::IterativeRobotBase::TeleopInit |
( |
| ) |
|
|
virtual |
Initialization code for teleop mode should go here.
Users should override this method for initialization code which will be called each time the robot enters teleop mode.
◆ TeleopPeriodic()
virtual void frc::IterativeRobotBase::TeleopPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for teleop mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in teleop mode.
◆ TestExit()
virtual void frc::IterativeRobotBase::TestExit |
( |
| ) |
|
|
virtual |
Exit code for test mode should go here.
Users should override this method for code which will be called each time the robot exits test mode.
◆ TestInit()
virtual void frc::IterativeRobotBase::TestInit |
( |
| ) |
|
|
virtual |
Initialization code for test mode should go here.
Users should override this method for initialization code which will be called each time the robot enters test mode.
◆ TestPeriodic()
virtual void frc::IterativeRobotBase::TestPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for test mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in test mode.
The documentation for this class was generated from the following file: