2 Commits

3 changed files with 12 additions and 12 deletions

View File

@@ -50,9 +50,9 @@ public class Climber extends SubsystemBase {
} }
public Command maintainPosition(ClimberPositions position) { public Command maintainPosition(ClimberPositions position) {
targetPosition = position;
return run(() -> { return run(() -> {
targetPosition = position;
controller.setSetpoint( controller.setSetpoint(
position.getPositionMeters(), position.getPositionMeters(),
ControlType.kPosition ControlType.kPosition
@@ -61,9 +61,9 @@ public class Climber extends SubsystemBase {
} }
public Command manualSpeed(DoubleSupplier speed) { public Command manualSpeed(DoubleSupplier speed) {
targetPosition = null;
return run(() -> { return run(() -> {
targetPosition = null;
motor.set(speed.getAsDouble()); motor.set(speed.getAsDouble());
}); });
} }

View File

@@ -60,9 +60,9 @@ public class IntakePivot extends SubsystemBase {
} }
public Command maintainPosition(IntakePivotPosition position) { public Command maintainPosition(IntakePivotPosition position) {
currentTargetPosition = position;
return run(() -> { return run(() -> {
currentTargetPosition = position;
if(currentTargetPosition == null) { if(currentTargetPosition == null) {
leftMotor.disable(); leftMotor.disable();
} else { } else {
@@ -72,9 +72,9 @@ public class IntakePivot extends SubsystemBase {
} }
public Command manualSpeed(DoubleSupplier speed) { public Command manualSpeed(DoubleSupplier speed) {
currentTargetPosition = null;
return run(() -> { return run(() -> {
currentTargetPosition = null;
leftMotor.set(speed.getAsDouble() * IntakePivotConstants.kMaxManualSpeedMultiplier); leftMotor.set(speed.getAsDouble() * IntakePivotConstants.kMaxManualSpeedMultiplier);
}); });
} }

View File

@@ -80,9 +80,9 @@ public class Shooter extends SubsystemBase {
} }
public Command maintainSpeed(ShooterSpeeds speeds) { public Command maintainSpeed(ShooterSpeeds speeds) {
targetSpeeds = speeds;
return run(() -> { return run(() -> {
targetSpeeds = speeds;
if(targetSpeeds == null) { if(targetSpeeds == null) {
leftMotor.disable(); leftMotor.disable();
rightMotor.disable(); rightMotor.disable();
@@ -101,9 +101,9 @@ public class Shooter extends SubsystemBase {
} }
public Command manualSpeed(DoubleSupplier speed) { public Command manualSpeed(DoubleSupplier speed) {
targetSpeeds = null;
return run(() -> { return run(() -> {
targetSpeeds = null;
leftMotor.set(speed.getAsDouble() * ShooterConstants.kMaxManualSpeedMultiplier); leftMotor.set(speed.getAsDouble() * ShooterConstants.kMaxManualSpeedMultiplier);
rightMotor.set(speed.getAsDouble() * ShooterConstants.kMaxManualSpeedMultiplier); rightMotor.set(speed.getAsDouble() * ShooterConstants.kMaxManualSpeedMultiplier);
}); });