Class IterativeRobotBase

  • All Implemented Interfaces:
    AutoCloseable
    Direct Known Subclasses:
    TimedRobot

    public abstract class IterativeRobotBase
    extends RobotBase
    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

    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()

    final() functions -- each of the following functions is called once when the appropriate mode is exited:

    • disabledExit() -- called each and every time disabled is exited
    • autonomousExit() -- called each and every time autonomous is exited
    • teleopExit() -- called each and every time teleop is exited
    • testExit() -- called each and every time test is exited
    • Constructor Detail

      • IterativeRobotBase

        protected IterativeRobotBase​(double period)
        Constructor for IterativeRobotBase.
        Parameters:
        period - Period in seconds.
    • Method Detail

      • 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.
      • disabledExit

        public void disabledExit()
        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.

      • autonomousExit

        public void autonomousExit()
        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.

      • teleopExit

        public void teleopExit()
        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.

      • testExit

        public void testExit()
        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.

      • 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
      • getPeriod

        public double getPeriod()
        Gets time period between calls to Periodic() functions.
        Returns:
        The time period between calls to Periodic() functions.