1
1
package frc .robot .shooter ;
2
2
3
+ import com .ctre .phoenix6 .controls .VelocityTorqueCurrentFOC ;
3
4
import com .ctre .phoenix6 .controls .VelocityVoltage ;
4
5
import com .ctre .phoenix6 .hardware .TalonFX ;
5
6
import dev .doglog .DogLog ;
@@ -14,8 +15,8 @@ public class ShooterSubsystem extends StateMachine<ShooterState> {
14
15
private final TalonFX bottomMotor ;
15
16
private double topMotorRpm ;
16
17
private double bottomMotorRpm ;
17
- private final VelocityVoltage velocityRequest =
18
- new VelocityVoltage (0 ).withEnableFOC ( false ).withLimitReverseMotion (true );
18
+ private final VelocityTorqueCurrentFOC velocityRequest =
19
+ new VelocityTorqueCurrentFOC (0 ).withSlot ( 0 ).withLimitReverseMotion (true );
19
20
private double distanceToSpeaker ;
20
21
private double distanceToFeedSpot ;
21
22
private InterpolatingDoubleTreeMap speakerDistanceToRpm = new InterpolatingDoubleTreeMap ();
@@ -138,5 +139,10 @@ public void robotPeriodic() {
138
139
DogLog .log ("Shooter/Bottom/SupplyCurrent" , bottomMotor .getSupplyCurrent ().getValueAsDouble ());
139
140
DogLog .log ("Shooter/Bottom/RPM" , bottomMotor .getVelocity ().getValueAsDouble () * 60.0 );
140
141
DogLog .log ("Shooter/Bottom/AppliedVoltage" , bottomMotor .getMotorVoltage ().getValueAsDouble ());
142
+
143
+ var goalRpm = topMotor .getClosedLoopReference ().getValueAsDouble () * 60.0 ;
144
+
145
+
146
+ DogLog .log ("Shooter/GoalRPM" , goalRpm );
141
147
}
142
148
}
0 commit comments