A bunch of changes, mostly related to shooting balls at the hub dynamically, still need a means of doing this based on a single apriltag, in the event the robot pose is unreliable
This commit is contained in:
@@ -48,12 +48,18 @@ public class Hood extends SubsystemBase {
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
public Command manualSpeed(DoubleSupplier speed) {
|
||||
currentTargetRadians = 0;
|
||||
|
||||
return run(() -> {
|
||||
motor.disable();
|
||||
motor.set(speed.getAsDouble() * HoodConstants.kMaxManualSpeedMultiplier);
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return manualSpeed(() -> 0);
|
||||
}
|
||||
|
||||
public double getTargetRadians() {
|
||||
return currentTargetRadians;
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user