Add thread code and example
This commit is contained in:
78
TeamCode/threaded/TaskThread.java
Normal file
78
TeamCode/threaded/TaskThread.java
Normal file
@ -0,0 +1,78 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.threadopmode;
|
||||||
|
|
||||||
|
public class TaskThread {
|
||||||
|
|
||||||
|
Actions actions;
|
||||||
|
int delay;
|
||||||
|
TaskRunnable taskRunnable;
|
||||||
|
|
||||||
|
/** Creates an object that contains code to be ran periodically on a separate thread
|
||||||
|
* Can be registered to a {@link ThreadOpMode} with {@link ThreadOpMode#registerThread(TaskThread)}
|
||||||
|
*
|
||||||
|
* @param actions An {@link Actions} interface that contains code to run periodically
|
||||||
|
* The default delay between runs is 0 milliseconds
|
||||||
|
*/
|
||||||
|
public TaskThread(Actions actions) {
|
||||||
|
this(0, actions);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Creates an object that contains code to be ran periodically on a separate thread.
|
||||||
|
* Can be registered to a {@link ThreadOpMode} with {@link ThreadOpMode#registerThread(TaskThread)}.
|
||||||
|
*
|
||||||
|
* @param delay The delay in milliseconds between each periodic run of the code.
|
||||||
|
* @param actions An {@link Actions} interface that contains code to run periodically.
|
||||||
|
*/
|
||||||
|
public TaskThread(int delay, Actions actions) {
|
||||||
|
this.actions = actions;
|
||||||
|
this.delay = delay;
|
||||||
|
this.taskRunnable = new TaskRunnable();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* An interface to be passed to a {@link TaskThread} constructor.
|
||||||
|
*/
|
||||||
|
public interface Actions {
|
||||||
|
/**
|
||||||
|
* Robot code to be ran periodically on its own thread.
|
||||||
|
*/
|
||||||
|
public void loop();
|
||||||
|
}
|
||||||
|
|
||||||
|
void start() {
|
||||||
|
taskRunnable.start();
|
||||||
|
}
|
||||||
|
|
||||||
|
void stop() {
|
||||||
|
taskRunnable.stop();
|
||||||
|
}
|
||||||
|
|
||||||
|
class TaskRunnable implements Runnable {
|
||||||
|
private Thread t;
|
||||||
|
|
||||||
|
TaskRunnable() {
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
public void run() {
|
||||||
|
try {
|
||||||
|
while(!t.isInterrupted()) {
|
||||||
|
actions.loop();
|
||||||
|
Thread.sleep(delay);
|
||||||
|
}
|
||||||
|
} catch (InterruptedException e) {
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void start() {
|
||||||
|
if (t == null) {
|
||||||
|
t = new Thread(this);
|
||||||
|
t.start();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
public void stop() {
|
||||||
|
t.interrupt();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
69
TeamCode/threaded/ThreadOpMode.java
Normal file
69
TeamCode/threaded/ThreadOpMode.java
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
package org.firstinspires.ftc.teamcode.threadopmode;
|
||||||
|
|
||||||
|
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||||
|
|
||||||
|
import java.util.ArrayList;
|
||||||
|
import java.util.List;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* A type of {@link OpMode} that contains threads to be ran in parallel periodically.
|
||||||
|
* Register threads with {@link ThreadOpMode#registerThread(TaskThread)}
|
||||||
|
*/
|
||||||
|
public abstract class ThreadOpMode extends OpMode {
|
||||||
|
private List<TaskThread> threads = new ArrayList<>();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Registers a new {@link TaskThread} to be ran periodically.
|
||||||
|
* Registered threads will automatically be started during {@link OpMode#start()} and stopped during {@link OpMode#stop()}.
|
||||||
|
*
|
||||||
|
* @param taskThread A {@link TaskThread} object to be ran periodically.
|
||||||
|
*/
|
||||||
|
public final void registerThread(TaskThread taskThread) {
|
||||||
|
threads.add(taskThread);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Contains code to be ran before the OpMode is started. Similar to {@link OpMode#init()}.
|
||||||
|
*/
|
||||||
|
public abstract void mainInit();
|
||||||
|
/**
|
||||||
|
* Contains code to be ran periodically in the MAIN thread. Similar to {@link OpMode#loop()}.
|
||||||
|
*/
|
||||||
|
public abstract void mainLoop();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Should not be called by subclass.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public final void init() {
|
||||||
|
mainInit();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Should not be called by subclass.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public final void start() {
|
||||||
|
for(TaskThread taskThread : threads) {
|
||||||
|
taskThread.start();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Should not be called by subclass.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public final void loop() {
|
||||||
|
mainLoop();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Should not be called by subclass.
|
||||||
|
*/
|
||||||
|
@Override
|
||||||
|
public final void stop() {
|
||||||
|
for(TaskThread taskThread : threads) {
|
||||||
|
taskThread.stop();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
31
TeamCode/threaded/example/ThreadedOpMode.java
Normal file
31
TeamCode/threaded/example/ThreadedOpMode.java
Normal file
@ -0,0 +1,31 @@
|
|||||||
|
import org.firstinspires.ftc.teamcode.threadopmode.*;
|
||||||
|
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||||
|
|
||||||
|
|
||||||
|
//Extend ThreadOpMode rather than OpMode
|
||||||
|
public class ThreadedOpMode extends ThreadOpMode {
|
||||||
|
|
||||||
|
//Define global variables
|
||||||
|
private DcMotor dcMotor;
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void mainInit() {
|
||||||
|
//Perform your normal init
|
||||||
|
dcMotor = hardwareMap.dcMotor.get("dcMotor");
|
||||||
|
|
||||||
|
//Below is a new thread
|
||||||
|
registerThread(new TaskThread(new TaskThread.Actions() {
|
||||||
|
@Override
|
||||||
|
public void loop() {
|
||||||
|
//The loop method should contain what to constantly run in the thread
|
||||||
|
//For instance, this drives a single DcMotor
|
||||||
|
dcMotor.setPower(gamepad1.left_stick_y);
|
||||||
|
}
|
||||||
|
}));
|
||||||
|
}
|
||||||
|
|
||||||
|
@Override
|
||||||
|
public void mainLoop() {
|
||||||
|
//Anything you want to constantly run in the MAIN thread goes here
|
||||||
|
}
|
||||||
|
}
|
Reference in New Issue
Block a user