|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |
java.lang.ObjectMIDlet
edu.wpi.first.wpilibj.RobotBase
edu.wpi.first.wpilibj.IterativeRobot
public class IterativeRobot
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 - TestInit() -- called each and every time test mode is entered from anothermode 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() - testPeriodoc()
Field Summary |
---|
Fields inherited from class edu.wpi.first.wpilibj.RobotBase |
---|
ERRORS_TO_DRIVERSTATION_PROP, FILE_NAME, m_ds, ROBOT_TASK_PRIORITY, VERSION_CONTENTS |
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 |
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 |
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 Users should override this method for code which will be called periodically at a regular rate while the robot is in test mode. |
Methods inherited from class edu.wpi.first.wpilibj.RobotBase |
---|
destroyApp, free, getBooleanProperty, getWatchdog, isAutonomous, isDisabled, isEnabled, isNewDataAvailable, isOperatorControl, isReal, isSimulation, isSystemActive, isTest, pauseApp, startApp, writeVersionString |
Methods inherited from class java.lang.Object |
---|
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait |
Constructor Detail |
---|
public IterativeRobot()
Method Detail |
---|
public void startCompetition()
startCompetition
in class RobotBase
public void robotInit()
public void disabledInit()
public void autonomousInit()
public void teleopInit()
public void testInit()
public void disabledPeriodic()
public void autonomousPeriodic()
public void teleopPeriodic()
public void testPeriodic()
|
|||||||||
PREV CLASS NEXT CLASS | FRAMES NO FRAMES | ||||||||
SUMMARY: NESTED | FIELD | CONSTR | METHOD | DETAIL: FIELD | CONSTR | METHOD |