File tree 6 files changed +53
-7
lines changed
src/main/java/org/team1540/robot2024
6 files changed +53
-7
lines changed Original file line number Diff line number Diff line change @@ -57,11 +57,11 @@ public static class Drivetrain {
57
57
}
58
58
public static class Indexer {
59
59
// 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 ;
65
65
public static final double FEEDER_KS = 0.0 ;
66
66
public static final double FEEDER_KV = 0.0 ;
67
67
public static final double FEEDER_GEAR_RATIO = 1.0 ;
Original file line number Diff line number Diff line change @@ -55,7 +55,7 @@ public Module(ModuleIO io, int index) {
55
55
56
56
public void periodic () {
57
57
io .updateInputs (inputs );
58
- Logger .processInputs ("Drive /Module" + index , inputs );
58
+ Logger .processInputs ("Drivetrain /Module" + index , inputs );
59
59
60
60
// On first cycle, reset relative turn encoder
61
61
// Wait until absolute angle is nonzero in case it wasn't initialized yet
Original file line number Diff line number Diff line change 5
5
import edu .wpi .first .wpilibj2 .command .Commands ;
6
6
import edu .wpi .first .wpilibj2 .command .SubsystemBase ;
7
7
import org .littletonrobotics .junction .Logger ;
8
+ import org .team1540 .robot2024 .util .LoggedTunableNumber ;
9
+ import static org .team1540 .robot2024 .Constants .Indexer .*;
8
10
9
11
10
12
public class Indexer extends SubsystemBase {
11
13
private final IndexerIO indexerIO ;
12
14
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
+
13
20
14
21
public Indexer (IndexerIO indexerIO ) {
15
22
this .indexerIO = indexerIO ;
@@ -18,6 +25,11 @@ public Indexer(IndexerIO indexerIO) {
18
25
public void periodic () {
19
26
indexerIO .updateInputs (indexerInputs );
20
27
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
+ }
21
33
}
22
34
23
35
public void setIntakePercent (double percent ) {
Original file line number Diff line number Diff line change @@ -13,6 +13,9 @@ class IndexerIOInputs {
13
13
public double feederCurrentAmps ;
14
14
public double feederVelocityRPM ;
15
15
public boolean noteInIntake = false ;
16
+ public double setpoint ;
17
+ public double feederVelocityRadPerSec ;
18
+ public double feederPositionError ;
16
19
}
17
20
18
21
/**
@@ -26,4 +29,6 @@ default void setFeederVoltage(double volts) {}
26
29
27
30
default void setFeederVelocity (double velocity ) {}
28
31
32
+ default void configurePID (double p , double i , double d ) {}
33
+
29
34
}
Original file line number Diff line number Diff line change @@ -28,9 +28,12 @@ public void updateInputs(IndexerIOInputs inputs) {
28
28
// inputs.feederVoltage = feederSim.getBusVoltage() * feederSim.getAppliedOutput();
29
29
inputs .feederVelocityRPM = feederSim .getAngularVelocityRPM ();
30
30
// inputs.noteInIntake = beamBreakSim.getBoolean("Indexer Beam Break").get();
31
+ inputs .setpoint = feederSimPID .getSetpoint ();
32
+ inputs .feederVelocityRadPerSec = feederSim .getAngularVelocityRadPerSec ();
33
+ inputs .feederPositionError = feederSimPID .getPositionError ();
31
34
32
35
// 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 ()));
34
37
35
38
}
36
39
@@ -44,6 +47,11 @@ public void setFeederVelocity(double velocity) {
44
47
feederSimPID .setSetpoint (velocity );
45
48
}
46
49
50
+ @ Override
51
+ public void configurePID (double p , double i , double d ) {
52
+ feederSimPID .setPID (p , i , d );
53
+ }
54
+
47
55
@ Override
48
56
public void setFeederVoltage (double volts ) {
49
57
feederSim .setInputVoltage (MathUtil .clamp (volts , -12 , 12 ));
Original file line number Diff line number Diff line change
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
+ }
You can’t perform that action at this time.
0 commit comments