Skip to content

Commit

Permalink
refactor the trigger wheel to have a desiredSpeed...
Browse files Browse the repository at this point in the history
rather than an enum
#30
  • Loading branch information
PatribotsProgramming committed Jan 24, 2024
1 parent 2ceff7d commit c56d916
Showing 1 changed file with 18 additions and 26 deletions.
44 changes: 18 additions & 26 deletions src/main/java/frc/robot/subsystems/Indexer.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,14 @@

public class Indexer extends SubsystemBase {
private final Neo triggerWheel;
private MotorRotation whichWay;
private double desiredSpeed;

public Indexer() {
triggerWheel = new Neo(IntakeConstants.TRIGGER_WHEEL_CAN_ID);
whichWay = MotorRotation.STOP;
desiredSpeed = 0;
configMotor();
}

enum MotorRotation {
CLOCKWISE,
COUNTER_CLOCKWISE,
STOP
}

public void configMotor() {
// See https://docs.revrobotics.com/sparkmax/operating-modes/control-interfaces
triggerWheel.setSmartCurrentLimit(IntakeConstants.TRIGGER_WHEEL_STALL_CURRENT_LIMIT_AMPS, IntakeConstants.TRIGGER_WHEEL_FREE_CURRENT_LIMIT_AMPS);
Expand All @@ -32,31 +26,29 @@ public void configMotor() {
//sets brake mode
triggerWheel.setBrakeMode();
}

public MotorRotation getWhichWay() {
return whichWay;

public double getDesiredSpeed() {
return desiredSpeed;
}

public void setDesiredSpeed(double speed) {
desiredSpeed = speed;
triggerWheel.set(speed);
}

public Command setSpeedCommand(double speed) {
return runOnce(() -> setDesiredSpeed(speed));
}

public Command toShooter() {
whichWay = MotorRotation.CLOCKWISE;
return runOnce(() -> triggerWheel.set(IntakeConstants.SHOOTER_TRIGGER_WHEEL_SPEED));
return setSpeedCommand(IntakeConstants.SHOOTER_TRIGGER_WHEEL_SPEED);
}

public Command toTrap() {
whichWay = MotorRotation.COUNTER_CLOCKWISE;
return runOnce(() -> triggerWheel.set(IntakeConstants.TRAP_TRIGGER_WHEEL_SPEED));
}

public Command stopCommand() {
whichWay = Optional.empty();
return runOnce(() -> triggerWheel.set(IntakeConstants.STOP_SPEED));
}

public BooleanSupplier hasPiece() {
return this.hasPiece;
return setSpeedCommand(IntakeConstants.TRAP_TRIGGER_WHEEL_SPEED);
}

public void setHasPiece(boolean hasPiece) {
this.hasPiece = () -> hasPiece;
public Command stopCommand() {
return setSpeedCommand(IntakeConstants.STOP_SPEED);
}
}

0 comments on commit c56d916

Please sign in to comment.