@@ -31,12 +31,13 @@ public class ShooterSubsystem extends SubsystemBase {
31
31
new TunableTelemetryPIDController ("/shooter/pid" , SHOOTER_PID_GAINS );
32
32
private final SimpleMotorFeedforward feedforward = SHOOTER_FF_GAINS .createFeedforward ();
33
33
34
- private final DoubleTelemetryEntry topFlyVoltageReq =
34
+ private final DoubleTelemetryEntry flyVoltageReq =
35
35
new DoubleTelemetryEntry ("/shooter/topVoltage" , false );
36
36
private final EventTelemetryEntry shooterEventEntry = new EventTelemetryEntry ("/shooter/events" );
37
37
38
38
public ShooterSubsystem () {
39
39
configMotor ();
40
+ setDefaultCommand (setVoltageCommand (0.0 ));
40
41
}
41
42
42
43
public void configMotor () {
@@ -82,18 +83,17 @@ public void configMotor() {
82
83
flywheelMotorAlert .set (faultInitializing );
83
84
}
84
85
85
- public void setFlyVoltage (double voltage ) {
86
+ public void setVoltage (double voltage ) {
87
+ flyVoltageReq .append (voltage );
86
88
flywheelMotor .setVoltage (voltage );
87
89
}
88
90
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 ));
93
93
}
94
94
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 ) ));
97
97
}
98
98
99
99
@ Override
0 commit comments