public abstract class LinearOpMode extends OpMode
This class derives from OpMode, but you should not override the methods from OpMode.
| Modifier and Type | Class and Description |
|---|---|
protected class |
LinearOpMode.LinearOpModeHelper |
| Constructor and Description |
|---|
LinearOpMode() |
| Modifier and Type | Method and Description |
|---|---|
protected void |
handleLoop() |
void |
idle()
Puts the current thread to sleep for a bit as it has nothing better to do.
|
void |
init_loop()
From the non-linear OpMode; do not override
|
void |
init()
From the non-linear OpMode; do not override
|
boolean |
isStarted()
Has the opMode been started?
|
boolean |
isStopRequested()
Has the the stopping of the opMode been requested?
|
void |
loop()
From the non-linear OpMode; do not override
|
boolean |
opModeIsActive()
Answer as to whether this opMode is active and the robot should continue onwards.
|
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()
Deprecated.
The need for user code to synchronize with the loop() thread has been
obviated by improvements in the modern motor and servo controller implementations.
Remaining uses of this API are likely unncessarily wasting cycles. If a simple non-zero
delay is required, the
sleep() method is a better choice.
If one simply wants to allow other threads to run, idle() is a good choice. |
void |
waitForStart()
Pause the Linear Op Mode until start has been pressed
|
void |
waitOneFullHardwareCycle()
Deprecated.
The need for user code to synchronize with the loop() thread has been
obviated by improvements in the modern motor and servo controller implementations.
Remaining uses of this API are likely unncessarily wasting cycles. If a simple non-zero
delay is required, the
sleep() method is a better choice.
If one simply wants to allow other threads to run, idle() is a good choice. |
getRuntime, requestOpModeStop, resetStartTime, updateTelemetry, updateTelemetryNowpublic 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.InterruptedExceptionpublic void waitForStart()
throws java.lang.InterruptedException
java.lang.InterruptedException@Deprecated
public void waitOneFullHardwareCycle()
throws java.lang.InterruptedException
sleep() method is a better choice.
If one simply wants to allow other threads to run, idle() is a good choice.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.InterruptedExceptionThread.sleep(long),
idle(),
waitForNextHardwareCycle()@Deprecated
public void waitForNextHardwareCycle()
throws java.lang.InterruptedException
sleep() method is a better choice.
If one simply wants to allow other threads to run, idle() is a good choice.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.InterruptedExceptionThread.sleep(long),
idle(),
waitOneFullHardwareCycle()public final void idle()
throws java.lang.InterruptedException
idle() is conceptually related to waitOneFullHardwareCycle(), but makes no
guarantees as to completing any particular number of hardware cycles, if any.java.lang.InterruptedException - thrown if the thread is interruptedwaitOneFullHardwareCycle()public final void sleep(long milliseconds)
throws java.lang.InterruptedException
sleep() method.milliseconds - amount of time to sleep, in millisecondsjava.lang.InterruptedExceptionThread.sleep(long)public final boolean opModeIsActive()
runOpMode() method and return to its caller.runOpMode(),
isStarted(),
isStopRequested()public final boolean isStarted()
opModeIsActive(),
isStopRequested()public final boolean isStopRequested()
opModeIsActive(),
isStarted()public final void init()
public final void init_loop()
public final void start()
public final void loop()
public final void stop()
protected void handleLoop()