Skip to content

Commit

Permalink
Thread leak fix and motorramping change
Browse files Browse the repository at this point in the history
  • Loading branch information
PrecociouslyDigital committed Mar 29, 2018
1 parent 79e2ae9 commit fd4c17a
Show file tree
Hide file tree
Showing 5 changed files with 40 additions and 24 deletions.
6 changes: 6 additions & 0 deletions src/main/java/com/github/dozer/coroutine/Task.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,15 @@
public abstract class Task extends Generator<BooleanSupplier> {

protected Waiters wait = new Waiters();
private boolean stop = false;

public BooleanSupplier waiter = () -> true;
public Iterator<BooleanSupplier> iterator;

@Override
protected void run() {
try {
if(this.stop) return;
runTask();
} catch (Throwable t) {
DriverStation.reportError("TASK CRASHED: " + this.getClass().getName() + " \n" + t.toString(),
Expand Down Expand Up @@ -46,4 +48,8 @@ public void untilWithTimeout(BooleanSupplier predicate, double secs) {
yield(() -> predicate.getAsBoolean() || finalTimeMillis < System.currentTimeMillis());
}
}

public void free(){
this.stop = true;
}
}
24 changes: 6 additions & 18 deletions src/main/java/com/github/dozer/coroutine/TaskRunner.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package com.github.dozer.coroutine;


import com.github.dozer.coroutine.helpers.RunParallelTask;
import java.util.Arrays;
import java.util.Iterator;
import java.util.LinkedList;
Expand All @@ -9,36 +10,23 @@

public class TaskRunner {

private List<Task> tasks;
private RunParallelTask mainTask;
private boolean disabled = false;

public TaskRunner(Task... tasks) {
this.tasks = new LinkedList<>();
this.tasks.addAll(Arrays.asList(tasks));
this.mainTask = new RunParallelTask(tasks);
}

public void run() {
if (disabled) {
return;
}

for (Iterator<Task> taskIterator = tasks.iterator(); taskIterator.hasNext();) {
Task task = taskIterator.next();
if (task.iterator == null) {
task.iterator = task.iterator();
}

if (task.waiter != null && task.waiter.getAsBoolean()) {
if (task.iterator.hasNext()) {
task.waiter = task.iterator.next();
} else {
taskIterator.remove();
}
}
}
}

public void disable() {
this.disabled = true;
}
public void free(){
this.mainTask.free();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -41,5 +41,12 @@ protected boolean runContinuously() {
}
return tasks.isEmpty();
}

public void free(){
for(Task task: tasks){
task.free();
}
super.free();
}
}

Original file line number Diff line number Diff line change
Expand Up @@ -20,4 +20,10 @@ protected void runTask() {
}
}
}
public void free(){
for(Task task: tasks){
task.free();
}
this.free();
}
}
21 changes: 15 additions & 6 deletions src/main/java/com/github/dozer/output/MotorRamping.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,23 @@

import edu.wpi.first.wpilibj.SpeedController;
import edu.wpi.first.wpilibj.PWMTalonSRX;
import edu.wpi.first.wpilibj.Timer;

public class MotorRamping implements Motor{
public static final double MOTOR_RAMPING = 0.01;

private SpeedController speedController;
private double motorRamping;
private double lastTime;

public MotorRamping(SpeedController speedController, boolean inverted) {
this(speedController, inverted, 5);
}

public MotorRamping(SpeedController speedController, boolean inverted, double rampPerSecond) {
this.speedController = speedController;
this.speedController.setInverted(inverted);
this.motorRamping = rampPerSecond;
this.lastTime = System.currentTimeMillis();
}

private double setpoint = 0;
Expand All @@ -32,12 +40,13 @@ public void stop() {
}

public void update() {
if (Math.abs(setpoint - current) < MOTOR_RAMPING) {
double moveAmount = motorRamping * (System.currentTimeMillis() - this.lastTime);
if (Math.abs(setpoint - current) < moveAmount) {
current = setpoint;
} else if (setpoint > current) {
current += MOTOR_RAMPING;
} else if (setpoint < current) {
current -= MOTOR_RAMPING;
} else if (setpoint > moveAmount) {
current += motorRamping;
} else if (setpoint < moveAmount) {
current -= motorRamping;
}
speedController.set(current);
}
Expand Down

0 comments on commit fd4c17a

Please sign in to comment.