public abstract class LinearOpMode extends OpMode
This class derives from OpMode, but you should not override the methods from OpMode.
Constructor and Description |
---|
LinearOpMode() |
Modifier and Type | Method and Description |
---|---|
void |
init_loop()
From the non-linear OpMode; do not override
|
void |
init()
From the non-linear OpMode; do not override
|
void |
loop()
From the non-linear OpMode; do not override
|
boolean |
opModeIsActive()
Returns true as long as the op mode is active.
|
abstract void |
runOpMode()
Override this method and place your code here.
|
void |
sleep(long milliseconds)
Sleep for the given amount of milliseconds
|
void |
start()
From the non-linear OpMode; do not override
|
void |
stop()
From the non-linear OpMode; do not override
|
void |
waitForNextHardwareCycle()
Wait for the start of the next hardware cycle
|
void |
waitForStart()
Pause the Linear Op Mode until start has been pressed
|
void |
waitOneFullHardwareCycle()
Wait for one full cycle of the hardware
|
getRuntime, resetStartTime
public abstract void runOpMode() throws java.lang.InterruptedException
Please do not swallow the InterruptedException, as it is used in cases where the op mode needs to be terminated early.
java.lang.InterruptedException
public void waitForStart() throws java.lang.InterruptedException
java.lang.InterruptedException
public void waitOneFullHardwareCycle() throws java.lang.InterruptedException
Each cycle of the hardware your commands are sent out to the hardware; and the latest data is read back in.
This method has a strong guarantee to wait for at least one full hardware hardware cycle.
java.lang.InterruptedException
public void waitForNextHardwareCycle() throws java.lang.InterruptedException
Each cycle of the hardware your commands are sent out to the hardware; and the latest data is read back in.
This method will wait for the current hardware cycle to finish, which is also the start of the next hardware cycle.
java.lang.InterruptedException
public void sleep(long milliseconds) throws java.lang.InterruptedException
milliseconds
- amount of time to sleepjava.lang.InterruptedException
public boolean opModeIsActive()
An op mode is considered active after the call to start() and before the call to stop().
public final void init()
public final void init_loop()
public final void start()
public final void loop()