Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Servo controller #85

Open
wants to merge 13 commits into
base: master
Choose a base branch
from
13 changes: 8 additions & 5 deletions src/com/nutrons/framework/StreamManager.java
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
package com.nutrons.framework;

import static com.nutrons.framework.util.CompMode.AUTO;
import static com.nutrons.framework.util.CompMode.TELE;
import static io.reactivex.Flowable.combineLatest;

import com.nutrons.framework.commands.Command;
import com.nutrons.framework.util.CompMode;
import io.reactivex.Flowable;
Expand All @@ -10,9 +14,7 @@
import java.util.List;
import java.util.function.Supplier;

import static com.nutrons.framework.util.CompMode.AUTO;
import static com.nutrons.framework.util.CompMode.TELE;
import static io.reactivex.Flowable.combineLatest;


/**
* This class sets up the I/O factories and initializes subsystems.
Expand All @@ -38,7 +40,7 @@ public StreamManager(Robot robot) {
* Subclasses should register subsystems in their constructor.
*
* @param enabled a Flowable of booleans, representing changes in the enabled state of the robot
* @param mode a Flowable of CompModes, representing changes in the competition game mode
* @param mode a Flowable of CompModes, representing changes in the competition game mode
*/
public StreamManager(Flowable<Boolean> enabled, Flowable<CompMode> mode) {
this.subsystems = new ArrayList<>();
Expand All @@ -50,7 +52,8 @@ public StreamManager(Flowable<Boolean> enabled, Flowable<CompMode> mode) {
* Called to by the bootstrapper to subscribe subsystem streams,
* and start the competition loop.
*/
public final void startCompetition(Supplier<Command> autoSupplier, Supplier<Command> teleopSupplier) {
public final void startCompetition(Supplier<Command> autoSupplier,
Supplier<Command> teleopSupplier) {
Observable.fromIterable(this.subsystems).blockingSubscribe(x -> {
System.out.println("registering " + x.getClass().getName());
x.registerSubscriptions();
Expand Down
35 changes: 24 additions & 11 deletions src/com/nutrons/framework/commands/Command.java
Original file line number Diff line number Diff line change
@@ -1,16 +1,15 @@
package com.nutrons.framework.commands;

import static com.nutrons.framework.util.FlowOperators.toFlow;

import io.reactivex.Flowable;
import io.reactivex.Observable;
import io.reactivex.disposables.Disposable;
import io.reactivex.flowables.ConnectableFlowable;
import io.reactivex.schedulers.Schedulers;
import org.reactivestreams.Publisher;

import java.util.concurrent.TimeUnit;
import java.util.function.Supplier;

import static com.nutrons.framework.util.FlowOperators.toFlow;
import org.reactivestreams.Publisher;

public class Command implements CommandWorkUnit {

Expand Down Expand Up @@ -81,13 +80,20 @@ public static Command fromSwitch(Publisher<? extends CommandWorkUnit> commandStr
return new Command(x -> Flowable.defer(() ->
Flowable.switchOnNext(Flowable.fromPublisher(commandStream).map(y -> y.execute(x))
.subscribeOn(Schedulers.io()))).scan((a, b) -> {
a.run();
return b;
}));
a.run();
return b;
}));
}

/**
* Adds a command that will terminate the current command.
* @param terminator Terminator command ou wish to add.
* @return teriminatable command.
*/
public Command addFinalTerminator(Terminator terminator) {
return Command.just(x -> this.source.execute(x).flatMap(y -> Flowable.<Terminator>just(y, terminator)).subscribeOn(Schedulers.io()));
return Command.just(
x -> this.source.execute(x).flatMap(y -> Flowable.<Terminator>just(y, terminator))
.subscribeOn(Schedulers.io()));
}

/**
Expand Down Expand Up @@ -120,8 +126,8 @@ public Command terminable(Publisher<?> terminator) {
/**
* Copies this command into one which will end when terminator emits an item.
*
* @param terminatesAtEnd if true, the command will terminate only when the end is reached,
* if false, the command may terminate before the end is reached.
* @param terminatesAtEnd if true, the command will terminate only when the end is reached, if
* false, the command may terminate before the end is reached.
*/
public Command endsWhen(Publisher<?> terminator, boolean terminatesAtEnd) {
return Command.just(x -> {
Expand All @@ -137,7 +143,8 @@ public Command endsWhen(Publisher<?> terminator, boolean terminatesAtEnd) {
* will only complete once endCondition returns true.
*/
public Command until(Supplier<Boolean> endCondition) {
ConnectableFlowable<?> terminator = emptyPulse.map(x -> endCondition.get()).filter(x -> x).onBackpressureDrop().publish();
ConnectableFlowable<?> terminator = emptyPulse.map(x -> endCondition.get()).filter(x -> x)
.onBackpressureDrop().publish();
terminator.connect();
return this.terminable(terminator);
}
Expand All @@ -163,6 +170,12 @@ public Command delayFinish(long delay, TimeUnit unit) {
return this.terminable(Flowable.timer(delay, unit));
}

/**
* Kills a command after a given time and unit
* @param delay a number in relation to a unit 1000 = 1 ms if unit is ms.
* @param unit unit you wish to count in.
* @return a command that will terminate after a given time.
*/
public Command killAfter(long delay, TimeUnit unit) {
return Command.just(x -> {
Flowable<Terminator> terms = this.terminable(Flowable.timer(delay, unit)).execute(x);
Expand Down
1 change: 1 addition & 0 deletions src/com/nutrons/framework/commands/CommandWorkUnit.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,5 +3,6 @@
import io.reactivex.Flowable;

public interface CommandWorkUnit {

Flowable<Terminator> execute(boolean selfTerminating);
}
1 change: 1 addition & 0 deletions src/com/nutrons/framework/commands/ParallelCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import io.reactivex.schedulers.Schedulers;

public class ParallelCommand implements CommandWorkUnit {

private final Flowable<Command> commands;

ParallelCommand(CommandWorkUnit... commands) {
Expand Down
1 change: 1 addition & 0 deletions src/com/nutrons/framework/commands/SerialCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import io.reactivex.schedulers.Schedulers;

public class SerialCommand implements CommandWorkUnit {

private final Flowable<Command> commands;

SerialCommand(CommandWorkUnit... commands) {
Expand Down
1 change: 1 addition & 0 deletions src/com/nutrons/framework/controllers/ControllerEvent.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,4 +11,5 @@ default void actOn(VirtualSpeedController controller) {
throw new EventUnimplementedException(
controller.getClass().toString(), this.getClass().toString());
}

}
2 changes: 2 additions & 0 deletions src/com/nutrons/framework/controllers/Events.java
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ public static ControllerEvent pid(double pval, double ival, double dval, double

/**
* Combines actions that are preformed on the talon.
*
* @return combined event
*/
public static ControllerEvent combine(ControllerEvent... events) {
Expand Down Expand Up @@ -94,4 +95,5 @@ public static ControllerEvent setOutputVoltage(double min, double max) {
public static ControllerEvent resetPosition(double position) {
return new ResetPositionEvent(position);
}

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Make a new class called ServoInstr

}
1 change: 1 addition & 0 deletions src/com/nutrons/framework/controllers/FollowEvent.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@ public class FollowEvent implements ControllerEvent {

/**
* Sets a LoopSpeedController to follow another LoopSpeedController
*
* @param targetToFollow is a LoopSpeedController which will be followed.
*/
public FollowEvent(LoopSpeedController targetToFollow) {
Expand Down
44 changes: 44 additions & 0 deletions src/com/nutrons/framework/controllers/RevServo.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
package com.nutrons.framework.controllers;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

JavaDoc


import edu.wpi.first.wpilibj.Servo;

/**
* The RevServo controlle used for the programming and running of Rev Smart Servos.
*/
public class RevServo extends ServoController {

private final Servo servo;

/**
* Makes a RevServo object at the given port.
*
* @param port Port of RevServo
*/
public RevServo(int port) {
servo = new Servo(port);
}

@Override
public void accept(ServoCommand servoCommand) {
servoCommand.actOn(this);
}

/**
* Sets the Servo to a given angle ranging from -90 to 90 left and right reflectively.
*
* @param angle given angle to turn to.
*/
public void setAngle(double angle) {
this.servo.setAngle(angle);
}

/**
* Set the motor to a position given a value 0.0 is full left 1.0 is full right.
*
* @param value The value to turn the servo to.
*/
public void set(double value) {
this.servo.set(value);
}

}
10 changes: 10 additions & 0 deletions src/com/nutrons/framework/controllers/ServoCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
package com.nutrons.framework.controllers;

public interface ServoCommand {

default void actOn(RevServo servo) {
throw new EventUnimplementedException(
servo.getClass().toString(), this.getClass().toString());
}

}
17 changes: 17 additions & 0 deletions src/com/nutrons/framework/controllers/ServoController.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
package com.nutrons.framework.controllers;

import io.reactivex.functions.Consumer;

public abstract class ServoController implements Consumer<ServoCommand> {

@Override
public abstract void accept(ServoCommand servoCommand);

public void setAngle(double angle) {
this.accept(ServoInstr.setAngle(angle));
}

public void set(double value) {
this.accept(ServoInstr.set(value));
}
}
13 changes: 13 additions & 0 deletions src/com/nutrons/framework/controllers/ServoInstr.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
package com.nutrons.framework.controllers;

public class ServoInstr {

public static ServoCommand setAngle(double angle) {
return new SetAngleCommand(angle);
}

public static ServoCommand set(double value) {
return new SetCommand(value);
}

}
31 changes: 31 additions & 0 deletions src/com/nutrons/framework/controllers/SetAngleCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
package com.nutrons.framework.controllers;

public class SetAngleCommand implements ServoCommand {

private final double angle;

/**
* An event which sets the servo to turn to a certain angle.
*
* @param angle the angle to turn the servo to -90 (left) to 90 (right).
*/
public SetAngleCommand(double angle) {
this.angle = angle;
}

public double angle() {
return this.angle;

}

@Override
public void actOn(RevServo servo) {
if (Math.abs(angle) > 90.0) {
throw new IllegalArgumentException(
"Angle greater than 90 degrees is not supported for Servos");
}
servo.setAngle(angle);

}

}
33 changes: 33 additions & 0 deletions src/com/nutrons/framework/controllers/SetCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
package com.nutrons.framework.controllers;

public class SetCommand implements ServoCommand {

private final double value;

/**
* An event which sets the servo to turn to a certain angle.
*
* @param value the input value to give the servo -1 is full left 1 is full right.
*/
public SetCommand(double value) {
this.value = value;

}

public double value() {
return this.value;

}

@Override
public void actOn(RevServo servo) {
if (Math.abs(value) > 1.0) {
throw new IllegalArgumentException(
"Value input greater than 1.0 is not supported for this servo");

}
servo.set(value);

}

}
6 changes: 3 additions & 3 deletions src/com/nutrons/framework/controllers/Talon.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
package com.nutrons.framework.controllers;

import static com.nutrons.framework.util.FlowOperators.toFlow;

import com.ctre.CANTalon;
import io.reactivex.Flowable;

import java.security.InvalidParameterException;

import static com.nutrons.framework.util.FlowOperators.toFlow;

public class Talon extends LoopSpeedController {

Expand Down Expand Up @@ -133,7 +133,7 @@ void resetPositionTo(double position) {


@Override
public boolean fwdLimitSwitchClosed(){
public boolean fwdLimitSwitchClosed() {
return this.talon.isFwdLimitSwitchClosed();
}

Expand Down
4 changes: 2 additions & 2 deletions src/com/nutrons/framework/inputs/Serial.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ public Serial(int bufferSize, int packetLength) {
* @param bufferSize represents how many bytes to cache unread before clearing buffer
* @param packetLength represents the length of each read from the buffer
* @param terminationCharacter allows users to set a custom termination character - default is the
* newline character '\n'
* newline character '\n'
*/
public Serial(SerialPort.Port port,
int bufferSize,
Expand All @@ -56,7 +56,7 @@ public Serial(SerialPort.Port port,
* @param bufferSize represents how many bytes to cache unread before clearing buffer
* @param packetLength represents the length of each read from the buffer
* @param terminationCharacter allows users to set a custom termination character - default is the
* newline character '\n'
* newline character '\n'
* @param baudrate See <a href="https://en.wikipedia.org/wiki/Symbol_rate">Symbol Rate</a>
*/
public Serial(int baudrate,
Expand Down
5 changes: 4 additions & 1 deletion src/com/nutrons/framework/subsystems/WpiSmartDashboard.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ public WpiSmartDashboard() {

/**
* Takes a double and passes it to the Smart Dashboard.
*
* @param key decimal passed to the Smartdash.
*/
public Consumer<Double> getTextFieldDouble(String key) {
Expand All @@ -39,7 +40,8 @@ public Consumer<Double> getTextFieldDouble(String key) {

/**
* Prints string to the Smart Dashborad.
* @param key A specific String.
*
* @param key A specific String.
*/
public Consumer<String> getTextFieldString(String key) {
if (!stringFields.containsKey(key)) {
Expand All @@ -54,6 +56,7 @@ public Consumer<String> getTextFieldString(String key) {

/**
* Prints Output of a Boolean to the Smart Dashboard.
*
* @param key boolean statement.
*/
public Consumer<Boolean> getTextFieldBoolean(String key) {
Expand Down
Loading