Class IterativeRobotBase

java.lang.Object
edu.wpi.first.wpilibj.RobotBase
edu.wpi.first.wpilibj.IterativeRobotBase
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()

  • Field Summary

    Fields inherited from class edu.wpi.first.wpilibj.RobotBase

    MAIN_THREAD_ID
  • Method Summary

    Modifier and Type Method Description
    void autonomousInit()
    Initialization code for autonomous mode should go here.
    void autonomousPeriodic()
    Periodic code for autonomous mode should go here.
    void disabledInit()
    Initialization code for disabled mode should go here.
    void disabledPeriodic()
    Periodic code for disabled mode should go here.
    void robotInit()
    Robot-wide initialization code should go here.
    void robotPeriodic()
    Periodic code for all robot modes should go here.
    abstract void startCompetition()
    Provide an alternate "main loop" via startCompetition().
    void teleopInit()
    Initialization code for teleop mode should go here.
    void teleopPeriodic()
    Periodic code for teleop mode should go here.
    void testInit()
    Initialization code for test mode should go here.
    void testPeriodic()
    Periodic code for test mode should go here.

    Methods inherited from class edu.wpi.first.wpilibj.RobotBase

    free, getBooleanProperty, isDisabled, isEnabled, startRobot

    Methods inherited from class java.lang.Object

    equals, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Method Details

    • startCompetition

      public abstract void startCompetition() throws java.lang.Exception
      Provide an alternate "main loop" via startCompetition().
      Specified by:
      startCompetition in class RobotBase
      Throws:
      java.lang.Exception
    • 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.

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

      public void disabledPeriodic() throws java.lang.Exception
      Periodic code for disabled mode should go here.
      Throws:
      java.lang.Exception
    • autonomousPeriodic

      public void autonomousPeriodic()
      Periodic code for autonomous mode should go here.
    • teleopPeriodic

      public void teleopPeriodic() throws java.lang.Exception
      Periodic code for teleop mode should go here.
      Throws:
      java.lang.Exception
    • testPeriodic

      public void testPeriodic()
      Periodic code for test mode should go here.