Skip to content
This repository was archived by the owner on Jan 10, 2025. It is now read-only.

Commit 04813c7

Browse files
Shooter bringup
1 parent 105caca commit 04813c7

File tree

2 files changed

+10
-4
lines changed

2 files changed

+10
-4
lines changed

src/main/java/frc/robot/config/CompConfig.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -61,15 +61,15 @@ class CompConfig {
6161
new CurrentLimitsConfigs()
6262
.withStatorCurrentLimit(40)
6363
.withSupplyCurrentLimit(45))
64-
.withSlot0(new Slot0Configs().withKV(0).withKP(0).withKI(0).withKD(0)),
64+
.withSlot0(new Slot0Configs().withKV(0.15).withKP(3.5).withKI(0).withKD(0)),
6565
new TalonFXConfiguration()
6666
.withClosedLoopRamps(CLOSED_LOOP_RAMP)
6767
.withOpenLoopRamps(OPEN_LOOP_RAMP)
6868
.withCurrentLimits(
6969
new CurrentLimitsConfigs()
7070
.withStatorCurrentLimit(40)
7171
.withSupplyCurrentLimit(45))
72-
.withSlot0(new Slot0Configs().withKV(0).withKP(0).withKI(0).withKD(0)),
72+
.withSlot0(new Slot0Configs().withKV(0.15).withKP(3.5).withKI(0).withKD(0)),
7373
feedSpotDistanceToRpm -> {
7474
feedSpotDistanceToRpm.put(123.0, 321.0);
7575
},

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

Lines changed: 8 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
package frc.robot.shooter;
22

3+
import com.ctre.phoenix6.controls.VelocityTorqueCurrentFOC;
34
import com.ctre.phoenix6.controls.VelocityVoltage;
45
import com.ctre.phoenix6.hardware.TalonFX;
56
import dev.doglog.DogLog;
@@ -14,8 +15,8 @@ public class ShooterSubsystem extends StateMachine<ShooterState> {
1415
private final TalonFX bottomMotor;
1516
private double topMotorRpm;
1617
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);
1920
private double distanceToSpeaker;
2021
private double distanceToFeedSpot;
2122
private InterpolatingDoubleTreeMap speakerDistanceToRpm = new InterpolatingDoubleTreeMap();
@@ -138,5 +139,10 @@ public void robotPeriodic() {
138139
DogLog.log("Shooter/Bottom/SupplyCurrent", bottomMotor.getSupplyCurrent().getValueAsDouble());
139140
DogLog.log("Shooter/Bottom/RPM", bottomMotor.getVelocity().getValueAsDouble() * 60.0);
140141
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);
141147
}
142148
}

0 commit comments

Comments
 (0)