Skip to content

Commit 98b86d2

Browse files
committed
Shooter stuff
1 parent add8c1b commit 98b86d2

File tree

1 file changed

+8
-8
lines changed

1 file changed

+8
-8
lines changed

src/main/java/frc/robot/subsystems/shooter/ShooterSubsystem.java

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,13 @@ public class ShooterSubsystem extends SubsystemBase {
3131
new TunableTelemetryPIDController("/shooter/pid", SHOOTER_PID_GAINS);
3232
private final SimpleMotorFeedforward feedforward = SHOOTER_FF_GAINS.createFeedforward();
3333

34-
private final DoubleTelemetryEntry topFlyVoltageReq =
34+
private final DoubleTelemetryEntry flyVoltageReq =
3535
new DoubleTelemetryEntry("/shooter/topVoltage", false);
3636
private final EventTelemetryEntry shooterEventEntry = new EventTelemetryEntry("/shooter/events");
3737

3838
public ShooterSubsystem() {
3939
configMotor();
40+
setDefaultCommand(setVoltageCommand(0.0));
4041
}
4142

4243
public void configMotor() {
@@ -82,18 +83,17 @@ public void configMotor() {
8283
flywheelMotorAlert.set(faultInitializing);
8384
}
8485

85-
public void setFlyVoltage(double voltage) {
86+
public void setVoltage(double voltage) {
87+
flyVoltageReq.append(voltage);
8688
flywheelMotor.setVoltage(voltage);
8789
}
8890

89-
public void setRPM(double rpm) {
90-
double forwardVol = feedforward.calculate(rpm);
91-
92-
setFlyVoltage(forwardVol);
91+
public Command setVoltageCommand(double voltage) {
92+
return this.run(() -> setVoltage(voltage));
9393
}
9494

95-
public Command runRPMCommand(double RPM) {
96-
return this.run(() -> this.setRPM(RPM));
95+
public Command runVelocityCommand(double setpointRotationsPerSecond) {
96+
return this.run(() -> setVoltage(pidController.calculate(flywheelEncoder.getVelocity(), setpointRotationsPerSecond) + feedforward.calculate(setpointRotationsPerSecond)));
9797
}
9898

9999
@Override

0 commit comments

Comments
 (0)