Skip to content

Commit

Permalink
Renaming + button bindings done
Browse files Browse the repository at this point in the history
  • Loading branch information
Ith9 committed Dec 4, 2024
1 parent cf86e76 commit 4544f02
Show file tree
Hide file tree
Showing 5 changed files with 109 additions and 90 deletions.
21 changes: 20 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
import frc.robot.subsystems.elevator.ElevatorConstants;
import frc.robot.subsystems.elevator.ElevatorIO;
import frc.robot.subsystems.elevator.ElevatorIOTalonFX;
import frc.robot.subsystems.elevator.ElevatorIOTalonFX;
import frc.robot.subsystems.elevator.Elevator.ElevatorVelocityTarget;
import frc.robot.subsystems.flywheels.Flywheels;
import frc.robot.subsystems.flywheels.FlywheelsIO;
import frc.robot.subsystems.flywheels.Flywheels.VelocityTarget;
Expand Down Expand Up @@ -143,6 +143,25 @@ private void configureBindings() {
flywheels.setVelocityTarget(VelocityTarget.IDLE);
},
flywheels));

// -----Elevator Controls-----
//
driverA
.rightTrigger()
.onTrue(
new InstantCommand(
() -> {
elevator.setVelocityTarget(ElevatorVelocityTarget.UP);
},
elevator));
driverA
.leftTrigger()
.onTrue(
new InstantCommand(
() -> {
elevator.setVelocityTarget(ElevatorVelocityTarget.DOWN);
},
elevator));
}

private void configureAutos() {}
Expand Down
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/subsystems/elevator/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,23 +6,23 @@

public class Elevator extends SubsystemBase {
// RPM
public enum VelocityTarget {
public enum ElevatorVelocityTarget {
IDLE(0, 0),
SHOOT(7500, 7500),
SLOW(1200, 1200);
private int topVelocity, bottomVelocity;
UP(7500, 7500),
DOWN(1200, 1200);
private int leftVelocity, rightVelocity;

private VelocityTarget(int topVelocity, int bottomVelocity) {
this.topVelocity = topVelocity;
this.bottomVelocity = bottomVelocity;
private ElevatorVelocityTarget(int leftVelocity, int rightVelocity) {
this.leftVelocity = leftVelocity;
this.rightVelocity = rightVelocity;
}
}

private final ElevatorIO io;
private final ElevatorIOInputsAutoLogged inputs = new ElevatorIOInputsAutoLogged();

@AutoLogOutput(key = "Mechanism/Elevator/Target")
private VelocityTarget velocityTarget = VelocityTarget.IDLE;
private ElevatorVelocityTarget velocityTarget = ElevatorVelocityTarget.IDLE;

public Elevator(ElevatorIO io) {
this.io = io;
Expand All @@ -33,13 +33,13 @@ public void periodic() {
io.updateInputs(inputs);
Logger.processInputs("Mechanism/Elevator", inputs);

io.runVelocity(velocityTarget.topVelocity, velocityTarget.bottomVelocity);
io.runVelocity(velocityTarget.leftVelocity, velocityTarget.rightVelocity);

Logger.recordOutput("Mechanism/Elevator/TopTargetVelocity", velocityTarget.topVelocity);
Logger.recordOutput("Mechanism/Elevator/BottomTargetVelocity", velocityTarget.bottomVelocity);
Logger.recordOutput("Mechanism/Elevator/leftTargetVelocity", velocityTarget.leftVelocity);
Logger.recordOutput("Mechanism/Elevator/rightTargetVelocity", velocityTarget.rightVelocity);
}

public void setVelocityTarget(VelocityTarget target) {
public void setVelocityTarget(ElevatorVelocityTarget target) {
velocityTarget = target;
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ public class ElevatorConstants {
case SIM -> new PIDGains(0, 0, 0, 0, 0, 0);
};

public record ElevatorConfig(int topID, int bottomID, double reduction) {}
public record ElevatorConfig(int leftID, int rightID, double reduction) {}

public record PIDGains(double kP, double kI, double kD, double kS, double kV, double kA) {}
}
32 changes: 16 additions & 16 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,26 +5,26 @@
public interface ElevatorIO {
@AutoLog
class ElevatorIOInputs {
public boolean topMotorConnected = true;
public boolean bottomMotorConnected = true;

public double topPositionRads = 0;
public double topVelocityRPM = 0;
public double topAppliedVolts = 0;
public double topSupplyCurrent = 0;
public double topTempCelcius = 0;

public double bottomPositionRads = 0;
public double bottomVelocityRPM = 0;
public double bottomAppliedVolts = 0;
public double bottomSupplyCurrent = 0;
public double bottomTempCelcius = 0;
public boolean leftMotorConnected = true;
public boolean rightMotorConnected = true;

public double leftPositionRads = 0;
public double leftVelocityRPM = 0;
public double leftAppliedVolts = 0;
public double leftSupplyCurrent = 0;
public double leftTempCelcius = 0;

public double rightPositionRads = 0;
public double rightVelocityRPM = 0;
public double rightAppliedVolts = 0;
public double rightSupplyCurrent = 0;
public double rightTempCelcius = 0;
}

default void updateInputs(ElevatorIOInputs inputs) {}

/* Run top and bottom flywheels at target velocities (RPM) */
default void runVelocity(int topRPM, int bottomRPM) {}
/* Run left and right motors at target velocities (RPM) */
default void runVelocity(int leftRPM, int rightRPM) {}

/* set slot0 (PID + ff) for both motors */
default void setSlot0(double kP, double kI, double kD, double kS, double kV, double kA) {}
Expand Down
120 changes: 60 additions & 60 deletions src/main/java/frc/robot/subsystems/elevator/ElevatorIOTalonFX.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,27 +13,27 @@
import edu.wpi.first.math.util.Units;

public class ElevatorIOTalonFX implements ElevatorIO {
private final TalonFX topTalon;
private final TalonFX bottomTalon;

private final StatusSignal<Double> topPositionRads;
private final StatusSignal<Double> topVelocityRPM;
private final StatusSignal<Double> topAppliedVolts;
private final StatusSignal<Double> topSupplyCurrent;
private final StatusSignal<Double> topTemp;
private final StatusSignal<Double> bottomPositionRads;
private final StatusSignal<Double> bottomVelocityRPM;
private final StatusSignal<Double> bottomAppliedVolts;
private final StatusSignal<Double> bottomSupplyCurrent;
private final StatusSignal<Double> bottomTemp;
private final TalonFX leftTalon;
private final TalonFX rightTalon;

private final StatusSignal<Double> leftPositionRads;
private final StatusSignal<Double> leftVelocityRPM;
private final StatusSignal<Double> leftAppliedVolts;
private final StatusSignal<Double> leftSupplyCurrent;
private final StatusSignal<Double> leftTemp;
private final StatusSignal<Double> rightPositionRads;
private final StatusSignal<Double> rightVelocityRPM;
private final StatusSignal<Double> rightAppliedVolts;
private final StatusSignal<Double> rightSupplyCurrent;
private final StatusSignal<Double> rightTemp;

private final Slot0Configs gainsConfig = new Slot0Configs();
private final VelocityVoltage velocityOutput = new VelocityVoltage(0).withUpdateFreqHz(0);
private final NeutralOut neutralOutput = new NeutralOut();

public ElevatorIOTalonFX() {
topTalon = new TalonFX(ELEVATOR_CONFIG.topID());
bottomTalon = new TalonFX(ELEVATOR_CONFIG.bottomID());
leftTalon = new TalonFX(ELEVATOR_CONFIG.leftID());
rightTalon = new TalonFX(ELEVATOR_CONFIG.rightID());

TalonFXConfiguration config = new TalonFXConfiguration();
config.CurrentLimits.SupplyCurrentLimit = 60.0; // FIXME
Expand All @@ -48,59 +48,59 @@ public ElevatorIOTalonFX() {
gainsConfig.kV = GAINS.kV();
gainsConfig.kA = GAINS.kA();

topTalon.getConfigurator().apply(config);
bottomTalon.getConfigurator().apply(config);
topTalon.getConfigurator().apply(gainsConfig);
bottomTalon.getConfigurator().apply(gainsConfig);

topTalon.setInverted(true);
bottomTalon.setInverted(true); // FIXME

topPositionRads = topTalon.getPosition();
topVelocityRPM = topTalon.getVelocity();
topAppliedVolts = topTalon.getMotorVoltage();
topSupplyCurrent = topTalon.getSupplyCurrent();
topTemp = topTalon.getDeviceTemp();

bottomPositionRads = bottomTalon.getPosition();
bottomVelocityRPM = bottomTalon.getVelocity();
bottomAppliedVolts = bottomTalon.getMotorVoltage();
bottomSupplyCurrent = bottomTalon.getSupplyCurrent();
bottomTemp = bottomTalon.getDeviceTemp();
leftTalon.getConfigurator().apply(config);
rightTalon.getConfigurator().apply(config);
leftTalon.getConfigurator().apply(gainsConfig);
rightTalon.getConfigurator().apply(gainsConfig);

leftTalon.setInverted(true);
rightTalon.setInverted(true); // FIXME

leftPositionRads = leftTalon.getPosition();
leftVelocityRPM = leftTalon.getVelocity();
leftAppliedVolts = leftTalon.getMotorVoltage();
leftSupplyCurrent = leftTalon.getSupplyCurrent();
leftTemp = leftTalon.getDeviceTemp();

rightPositionRads = rightTalon.getPosition();
rightVelocityRPM = rightTalon.getVelocity();
rightAppliedVolts = rightTalon.getMotorVoltage();
rightSupplyCurrent = rightTalon.getSupplyCurrent();
rightTemp = rightTalon.getDeviceTemp();
}

@Override
public void updateInputs(ElevatorIOInputs inputs) {
inputs.topMotorConnected =
inputs.leftMotorConnected =
BaseStatusSignal.refreshAll(
topPositionRads, topVelocityRPM, topAppliedVolts, topSupplyCurrent, topTemp)
leftPositionRads, leftVelocityRPM, leftAppliedVolts, leftSupplyCurrent, leftTemp)
.isOK();
inputs.bottomMotorConnected =
inputs.rightMotorConnected =
BaseStatusSignal.refreshAll(
bottomPositionRads,
bottomVelocityRPM,
bottomAppliedVolts,
bottomSupplyCurrent,
bottomTemp)
rightPositionRads,
rightVelocityRPM,
rightAppliedVolts,
rightSupplyCurrent,
rightTemp)
.isOK();

inputs.topPositionRads = Units.rotationsToRadians(topPositionRads.getValueAsDouble());
inputs.topVelocityRPM = topVelocityRPM.getValueAsDouble() * 60.0;
inputs.topAppliedVolts = topAppliedVolts.getValueAsDouble();
inputs.topSupplyCurrent = topSupplyCurrent.getValueAsDouble();
inputs.topTempCelcius = topTemp.getValueAsDouble();

inputs.bottomPositionRads = Units.rotationsToRadians(bottomPositionRads.getValueAsDouble());
inputs.bottomVelocityRPM = bottomVelocityRPM.getValueAsDouble() * 60.0;
inputs.bottomAppliedVolts = bottomAppliedVolts.getValueAsDouble();
inputs.bottomSupplyCurrent = bottomSupplyCurrent.getValueAsDouble();
inputs.bottomTempCelcius = bottomTemp.getValueAsDouble();
inputs.leftPositionRads = Units.rotationsToRadians(leftPositionRads.getValueAsDouble());
inputs.leftVelocityRPM = leftVelocityRPM.getValueAsDouble() * 60.0;
inputs.leftAppliedVolts = leftAppliedVolts.getValueAsDouble();
inputs.leftSupplyCurrent = leftSupplyCurrent.getValueAsDouble();
inputs.leftTempCelcius = leftTemp.getValueAsDouble();

inputs.rightPositionRads = Units.rotationsToRadians(rightPositionRads.getValueAsDouble());
inputs.rightVelocityRPM = rightVelocityRPM.getValueAsDouble() * 60.0;
inputs.rightAppliedVolts = rightAppliedVolts.getValueAsDouble();
inputs.rightSupplyCurrent = rightSupplyCurrent.getValueAsDouble();
inputs.rightTempCelcius = rightTemp.getValueAsDouble();
}

@Override
public void runVelocity(int topVelocity, int bottomVelocity) {
topTalon.setControl(velocityOutput.withVelocity(topVelocity / 60));
bottomTalon.setControl(velocityOutput.withVelocity(bottomVelocity / 60));
public void runVelocity(int leftVelocity, int rightVelocity) {
leftTalon.setControl(velocityOutput.withVelocity(leftVelocity / 60));
rightTalon.setControl(velocityOutput.withVelocity(rightVelocity / 60));
}

@Override
Expand All @@ -112,13 +112,13 @@ public void setSlot0(double kP, double kI, double kD, double kS, double kV, doub
gainsConfig.kV = kV;
gainsConfig.kA = kA;

topTalon.getConfigurator().apply(gainsConfig);
bottomTalon.getConfigurator().apply(gainsConfig);
leftTalon.getConfigurator().apply(gainsConfig);
rightTalon.getConfigurator().apply(gainsConfig);
}

@Override
public void stop() {
topTalon.setControl(neutralOutput);
bottomTalon.setControl(neutralOutput);
leftTalon.setControl(neutralOutput);
rightTalon.setControl(neutralOutput);
}
}

0 comments on commit 4544f02

Please sign in to comment.