Skip to content

Commit b906548

Browse files
committed
fix: made simulation somewhat working
1 parent 32361a9 commit b906548

File tree

6 files changed

+53
-7
lines changed

6 files changed

+53
-7
lines changed

src/main/java/org/team1540/robot2024/Constants.java

+5-5
Original file line numberDiff line numberDiff line change
@@ -57,11 +57,11 @@ public static class Drivetrain {
5757
}
5858
public static class Indexer {
5959
// TODO: fix these constants
60-
public static final int INTAKE_ID = 0;
61-
public static final int FEEDER_ID = 0;
62-
public static final double FEEDER_KP = 0.0;
63-
public static final double FEEDER_KI = 0.0;
64-
public static final double FEEDER_KD = 0.0;
60+
public static final int INTAKE_ID = 11;
61+
public static final int FEEDER_ID = 12;
62+
public static final double FEEDER_KP = 0.5;
63+
public static final double FEEDER_KI = 0.1;
64+
public static final double FEEDER_KD = 0.001;
6565
public static final double FEEDER_KS = 0.0;
6666
public static final double FEEDER_KV = 0.0;
6767
public static final double FEEDER_GEAR_RATIO = 1.0;

src/main/java/org/team1540/robot2024/subsystems/drive/Module.java

+1-1
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ public Module(ModuleIO io, int index) {
5555

5656
public void periodic() {
5757
io.updateInputs(inputs);
58-
Logger.processInputs("Drive/Module" + index, inputs);
58+
Logger.processInputs("Drivetrain/Module" + index, inputs);
5959

6060
// On first cycle, reset relative turn encoder
6161
// Wait until absolute angle is nonzero in case it wasn't initialized yet

src/main/java/org/team1540/robot2024/subsystems/indexer/Indexer.java

+12
Original file line numberDiff line numberDiff line change
@@ -5,11 +5,18 @@
55
import edu.wpi.first.wpilibj2.command.Commands;
66
import edu.wpi.first.wpilibj2.command.SubsystemBase;
77
import org.littletonrobotics.junction.Logger;
8+
import org.team1540.robot2024.util.LoggedTunableNumber;
9+
import static org.team1540.robot2024.Constants.Indexer.*;
810

911

1012
public class Indexer extends SubsystemBase {
1113
private final IndexerIO indexerIO;
1214
private final IndexerIOInputsAutoLogged indexerInputs = new IndexerIOInputsAutoLogged();
15+
private final boolean TUNING = true;
16+
private final LoggedTunableNumber kP = new LoggedTunableNumber("Indexer/kP", FEEDER_KP);
17+
private final LoggedTunableNumber kI = new LoggedTunableNumber("Indexer/kI", FEEDER_KI);
18+
private final LoggedTunableNumber kD = new LoggedTunableNumber("Indexer/kD", FEEDER_KD);
19+
1320

1421
public Indexer(IndexerIO indexerIO) {
1522
this.indexerIO = indexerIO;
@@ -18,6 +25,11 @@ public Indexer(IndexerIO indexerIO) {
1825
public void periodic() {
1926
indexerIO.updateInputs(indexerInputs);
2027
Logger.processInputs("Indexer", indexerInputs);
28+
if (TUNING) {
29+
if (kP.hasChanged() || kI.hasChanged() || kD.hasChanged()) {
30+
indexerIO.configurePID(kP.get(), kI.get(), kD.get());
31+
}
32+
}
2133
}
2234

2335
public void setIntakePercent(double percent) {

src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIO.java

+5
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,9 @@ class IndexerIOInputs {
1313
public double feederCurrentAmps;
1414
public double feederVelocityRPM;
1515
public boolean noteInIntake = false;
16+
public double setpoint;
17+
public double feederVelocityRadPerSec;
18+
public double feederPositionError;
1619
}
1720

1821
/**
@@ -26,4 +29,6 @@ default void setFeederVoltage(double volts) {}
2629

2730
default void setFeederVelocity(double velocity) {}
2831

32+
default void configurePID(double p, double i, double d) {}
33+
2934
}

src/main/java/org/team1540/robot2024/subsystems/indexer/IndexerIOSim.java

+9-1
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,12 @@ public void updateInputs(IndexerIOInputs inputs) {
2828
// inputs.feederVoltage = feederSim.getBusVoltage() * feederSim.getAppliedOutput();
2929
inputs.feederVelocityRPM = feederSim.getAngularVelocityRPM();
3030
// inputs.noteInIntake = beamBreakSim.getBoolean("Indexer Beam Break").get();
31+
inputs.setpoint = feederSimPID.getSetpoint();
32+
inputs.feederVelocityRadPerSec = feederSim.getAngularVelocityRadPerSec();
33+
inputs.feederPositionError = feederSimPID.getPositionError();
3134

3235
// this is a very funny line of code, and absolutely does not belong here, but I don't know how to do this otherwise
33-
feederSim.setState(feederSim.getAngularPositionRad(), feederSimPID.calculate(feederSim.getAngularVelocityRadPerSec()));
36+
feederSim.setState(feederSim.getAngularPositionRad(), feederSim.getAngularVelocityRadPerSec() + feederSimPID.calculate(feederSim.getAngularVelocityRadPerSec()));
3437

3538
}
3639

@@ -44,6 +47,11 @@ public void setFeederVelocity(double velocity) {
4447
feederSimPID.setSetpoint(velocity);
4548
}
4649

50+
@Override
51+
public void configurePID(double p, double i, double d) {
52+
feederSimPID.setPID(p, i, d);
53+
}
54+
4755
@Override
4856
public void setFeederVoltage(double volts) {
4957
feederSim.setInputVoltage(MathUtil.clamp(volts, -12, 12));
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,21 @@
1+
package org.team1540.robot2024.util;
2+
3+
import org.littletonrobotics.junction.networktables.LoggedDashboardNumber;
4+
5+
public class LoggedTunableNumber extends LoggedDashboardNumber {
6+
private double lastHasChangedValue;
7+
8+
public LoggedTunableNumber(String key, double defaultValue) {
9+
super(key, defaultValue);
10+
lastHasChangedValue = defaultValue;
11+
}
12+
13+
public boolean hasChanged() {
14+
double currentValue = get();
15+
if (currentValue != lastHasChangedValue) {
16+
lastHasChangedValue = currentValue;
17+
return true;
18+
}
19+
return false;
20+
}
21+
}

0 commit comments

Comments
 (0)