edu.wpi.first.wpilibj
Class IterativeRobot

java.lang.Object
  extended by javax.microedition.midlet.MIDlet
      extended by edu.wpi.first.wpilibj.RobotBase
          extended by edu.wpi.first.wpilibj.IterativeRobot

public class IterativeRobot
extends RobotBase

IterativeRobot implements a specific type of Robot Program framework, extending the RobotBase class. The IterativeRobot class is intended to be subclassed by a user creating a robot program. This class is intended to implement the "old style" default code, by providing 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 only when first disabled - AutonomousInit() -- called each and every time autonomous is entered from another mode - TeleopInit() -- called each and every time teleop is entered from another mode Periodic() functions -- each of these functions is called iteratively at the appropriate periodic rate (aka the "slow loop"). The period of the iterative robot is synced to the driver station control packets, giving a periodic frequency of about 50Hz (50 times per second). - disabledPeriodic() - autonomousPeriodic() - teleopPeriodic() Continuous() functions -- each of these functions is called repeatedly as fast as possible: - disabledContinuous() - autonomousContinuous() - teleopContinuous()


Field Summary
 
Fields inherited from class edu.wpi.first.wpilibj.RobotBase
ERRORS_TO_DRIVERSTATION_PROP, m_ds, ROBOT_TASK_PRIORITY
 
Constructor Summary
IterativeRobot()
          Constructor for RobotIterativeBase The constructor initializes the instance variables for the robot to indicate the status of initialization for disabled, autonomous, and teleop code.
 
Method Summary
 void autonomousContinuous()
          Continuous code for autonomous mode should go here.
 void autonomousInit()
          Initialization code for autonomous mode should go here.
 void autonomousPeriodic()
          Periodic code for autonomous mode should go here.
 void disabledContinuous()
          Continuous code for disabled 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 startCompetition()
          Provide an alternate "main loop" via startCompetition().
 void teleopContinuous()
          Continuous code for teleop mode should go here.
 void teleopInit()
          Initialization code for teleop mode should go here.
 void teleopPeriodic()
          Periodic code for teleop mode should go here.
 
Methods inherited from class edu.wpi.first.wpilibj.RobotBase
destroyApp, free, getBooleanProperty, getWatchdog, isAutonomous, isDisabled, isEnabled, isNewDataAvailable, isOperatorControl, isSystemActive, pauseApp, startApp
 
Methods inherited from class javax.microedition.midlet.MIDlet
runMIDlet
 
Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
 

Constructor Detail

IterativeRobot

public IterativeRobot()
Constructor for RobotIterativeBase The constructor initializes the instance variables for the robot to indicate the status of initialization for disabled, autonomous, and teleop code.

Method Detail

startCompetition

public void startCompetition()
Provide an alternate "main loop" via startCompetition(). This specific startCompetition() implements "main loop" behavior like that of the FRC control system in 2008 and earlier, with a primary (slow) loop that is called periodically, and a "fast loop" (a.k.a. "spin loop") that is called as fast as possible with no delay between calls.

Specified by:
startCompetition in class RobotBase

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 1 time.


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.


disabledPeriodic

public void disabledPeriodic()
Periodic code for disabled mode should go here. Users should override this method for code which will be called periodically at a regular rate while the robot is in disabled mode.


autonomousPeriodic

public void autonomousPeriodic()
Periodic code for autonomous mode should go here. Users should override this method for code which will be called periodically at a regular rate while the robot is in autonomous mode.


teleopPeriodic

public void teleopPeriodic()
Periodic code for teleop mode should go here. Users should override this method for code which will be called periodically at a regular rate while the robot is in teleop mode.


disabledContinuous

public void disabledContinuous()
Continuous code for disabled mode should go here. Users should override this method for code which will be called repeatedly as frequently as possible while the robot is in disabled mode.


autonomousContinuous

public void autonomousContinuous()
Continuous code for autonomous mode should go here. Users should override this method for code which will be called repeatedly as frequently as possible while the robot is in autonomous mode.


teleopContinuous

public void teleopContinuous()
Continuous code for teleop mode should go here. Users should override this method for code which will be called repeatedly as frequently as possible while the robot is in teleop mode.