Class IterativeRobotBase
- All Implemented Interfaces:
AutoCloseable
- Direct Known Subclasses:
IterativeRobot,TimedRobot
public abstract class IterativeRobotBase extends RobotBase
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
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: - robotPeriodic() - disabledPeriodic() - autonomousPeriodic() - teleopPeriodic() - testPeriodic()
-
Field Summary
Fields Modifier and Type Field Description protected doublem_period -
Constructor Summary
Constructors Modifier Constructor Description protectedIterativeRobotBase(double period)Constructor for IterativeRobotBase. -
Method Summary
Modifier and Type Method Description voidautonomousInit()Initialization code for autonomous mode should go here.voidautonomousPeriodic()Periodic code for autonomous mode should go here.voiddisabledInit()Initialization code for disabled mode should go here.voiddisabledPeriodic()Periodic code for disabled mode should go here.protected voidloopFunc()voidrobotInit()Robot-wide initialization code should go here.voidrobotPeriodic()Periodic code for all robot modes should go here.voidsetNetworkTablesFlushEnabled(boolean enabled)Enables or disables flushing NetworkTables every loop iteration.voidsimulationInit()Robot-wide simulation initialization code should go here.voidsimulationPeriodic()Periodic simulation code should go here.abstract voidstartCompetition()Provide an alternate "main loop" via startCompetition().voidteleopInit()Initialization code for teleop mode should go here.voidteleopPeriodic()Periodic code for teleop mode should go here.voidtestInit()Initialization code for test mode should go here.voidtestPeriodic()Periodic code for test mode should go here.Methods inherited from class edu.wpi.first.wpilibj.RobotBase
close, endCompetition, getBooleanProperty, getMainThreadId, isAutonomous, isAutonomousEnabled, isDisabled, isEnabled, isNewDataAvailable, isOperatorControl, isOperatorControlEnabled, isReal, isSimulation, isTest, startRobot, suppressExitWarning
-
Field Details
-
m_period
protected double m_period
-
-
Constructor Details
-
IterativeRobotBase
protected IterativeRobotBase(double period)Constructor for IterativeRobotBase.- Parameters:
period- Period in seconds.
-
-
Method Details
-
startCompetition
public abstract void startCompetition()Provide an alternate "main loop" via startCompetition().- Specified by:
startCompetitionin classRobotBase
-
robotInit
public void robotInit()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.
-
simulationInit
public void simulationInit()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.
-
disabledInit
public void disabledInit()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.
-
autonomousInit
public void autonomousInit()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.
-
teleopInit
public void teleopInit()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.
-
testInit
public void testInit()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.
-
robotPeriodic
public void robotPeriodic()Periodic code for all robot modes should go here. -
simulationPeriodic
public void simulationPeriodic()Periodic simulation code should go here.This function is called in a simulated robot after user code executes.
-
disabledPeriodic
public void disabledPeriodic()Periodic code for disabled mode should go here. -
autonomousPeriodic
public void autonomousPeriodic()Periodic code for autonomous mode should go here. -
teleopPeriodic
public void teleopPeriodic()Periodic code for teleop mode should go here. -
testPeriodic
public void testPeriodic()Periodic code for test mode should go here. -
setNetworkTablesFlushEnabled
public void setNetworkTablesFlushEnabled(boolean enabled)Enables or disables flushing NetworkTables every loop iteration. By default, this is disabled.- Parameters:
enabled- True to enable, false to disable
-
loopFunc
protected void loopFunc()
-