Skip to content

Commit bdbf385

Browse files
committed
updated mannual control to voltage
1 parent dfceb1c commit bdbf385

File tree

1 file changed

+17
-29
lines changed

1 file changed

+17
-29
lines changed

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

Lines changed: 17 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,9 @@
1010

1111
import com.ctre.phoenix6.configs.CurrentLimitsConfigs;
1212
import com.ctre.phoenix6.configs.TalonFXConfiguration;
13-
import com.ctre.phoenix6.controls.DutyCycleOut;
1413
import com.ctre.phoenix6.controls.NeutralOut;
1514
import com.ctre.phoenix6.controls.VelocityVoltage;
15+
import com.ctre.phoenix6.controls.VoltageOut;
1616
import com.ctre.phoenix6.hardware.TalonFX;
1717
import com.ctre.phoenix6.signals.InvertedValue;
1818
import edu.wpi.first.math.geometry.Rotation3d;
@@ -39,7 +39,7 @@ public class Shooter extends SubsystemBase {
3939

4040
VelocityVoltage velocityVoltage = new VelocityVoltage(0).withSlot(0);
4141
// VelocityTorqueCurrentFOC velocityTorque = new VelocityTorqueCurrentFOC(0).withSlot(1);
42-
DutyCycleOut dutyCycle = new DutyCycleOut(0);
42+
VoltageOut voltage = new VoltageOut(12 * 0.3);
4343
NeutralOut brake = new NeutralOut();
4444

4545
CurrentLimitsConfigs currentLimits = new CurrentLimitsConfigs();
@@ -68,6 +68,9 @@ public Shooter() {
6868
tryUntilOk(5, () -> flywheel.getConfigurator().apply(currentLimits));
6969

7070
SmartDashboard.putNumber("Shooter/Target RPS", 0.0);
71+
SmartDashboard.putNumber("Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
72+
SmartDashboard.putNumber("Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
73+
7174
}
7275

7376
public void intake() {} // for sim
@@ -226,13 +229,6 @@ public Command flywheelCMD(Supplier<Translation2d> distance) {
226229
() -> {
227230
targetRPS = calculateRR(distance.get());
228231
flywheel.setControl(velocityVoltage.withVelocity(targetRPS));
229-
SmartDashboard.putNumber(
230-
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
231-
SmartDashboard.putNumber(
232-
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
233-
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
234-
SmartDashboard.putNumber(
235-
"Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
236232
SmartDashboard.putNumber("Shooter/Distance", distance.get().getX());
237233
},
238234
this);
@@ -243,13 +239,6 @@ public Command flywheelGndCMD(DoubleSupplier distance) {
243239
() -> {
244240
targetRPS = calculateRRGround(distance.getAsDouble());
245241
flywheel.setControl(velocityVoltage.withVelocity(targetRPS));
246-
SmartDashboard.putNumber(
247-
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
248-
SmartDashboard.putNumber(
249-
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
250-
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
251-
SmartDashboard.putNumber(
252-
"Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
253242
SmartDashboard.putNumber("Shooter/Distance", distance.getAsDouble());
254243
},
255244
this);
@@ -260,13 +249,6 @@ public Command flywheelHubCMD(DoubleSupplier distance) {
260249
() -> {
261250
targetRPS = calculateRRHub(distance.getAsDouble());
262251
flywheel.setControl(velocityVoltage.withVelocity(targetRPS));
263-
SmartDashboard.putNumber(
264-
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
265-
SmartDashboard.putNumber(
266-
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
267-
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
268-
SmartDashboard.putNumber(
269-
"Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
270252
SmartDashboard.putNumber("Shooter/Distance", distance.getAsDouble());
271253
},
272254
this);
@@ -275,7 +257,7 @@ public Command flywheelHubCMD(DoubleSupplier distance) {
275257
public Command rawFlywheelCMD(DoubleSupplier drive) {
276258
return Commands.run(
277259
() -> {
278-
flywheel.setControl(dutyCycle.withOutput(drive.getAsDouble()));
260+
flywheel.setControl(voltage.withOutput(drive.getAsDouble() * 4));
279261
},
280262
this);
281263
}
@@ -288,6 +270,17 @@ public Command stopCMD() {
288270
this);
289271
}
290272

273+
@Override
274+
public void periodic() {
275+
SmartDashboard.putNumber(
276+
"Shooter/Flywheel/Voltage", flywheel.getMotorVoltage().getValueAsDouble());
277+
SmartDashboard.putNumber(
278+
"Shooter/Flywheel/Current", flywheel.getStatorCurrent().getValueAsDouble());
279+
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
280+
SmartDashboard.putNumber(
281+
"Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
282+
}
283+
291284
@Override
292285
public void simulationPeriodic() {
293286
SmartDashboard.putNumber(
@@ -297,9 +290,4 @@ public void simulationPeriodic() {
297290
SmartDashboard.putNumber("Shooter/Target RPS", targetRPS);
298291
SmartDashboard.putNumber("Shooter/Flywheel RPS", flywheel.getVelocity().getValueAsDouble());
299292
}
300-
301-
public Command flywheelHubCMD(Object object) {
302-
// TODO Auto-generated method stub
303-
throw new UnsupportedOperationException("Unimplemented method 'flywheelHubCMD'");
304-
}
305293
}

0 commit comments

Comments
 (0)