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

Commit 1aec0ef

Browse files
committed
[elevator] Merge constants
1 parent 113038d commit 1aec0ef

File tree

5 files changed

+47
-64
lines changed

5 files changed

+47
-64
lines changed

src/main/java/org/curtinfrc/frc2025/Autos.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@
1414
import org.curtinfrc.frc2025.subsystems.drive.DriveConstants.DriveSetpoints;
1515
import org.curtinfrc.frc2025.subsystems.ejector.Ejector;
1616
import org.curtinfrc.frc2025.subsystems.elevator.Elevator;
17-
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorConstants.ElevatorSetpoints;
17+
import org.curtinfrc.frc2025.subsystems.elevator.Elevator.ElevatorSetpoints;
1818
import org.curtinfrc.frc2025.subsystems.intake.Intake;
1919

2020
public class Autos {

src/main/java/org/curtinfrc/frc2025/Constants.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@
77
import edu.wpi.first.util.struct.StructSerializable;
88
import edu.wpi.first.wpilibj.RobotBase;
99
import org.curtinfrc.frc2025.subsystems.drive.DriveConstants.DriveSetpoints;
10-
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorConstants.ElevatorSetpoints;
10+
import org.curtinfrc.frc2025.subsystems.elevator.Elevator.ElevatorSetpoints;
1111

1212
/**
1313
* This class defines the runtime mode used by AdvantageKit. The mode is always "real" when running

src/main/java/org/curtinfrc/frc2025/Robot.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -45,7 +45,7 @@
4545
import org.curtinfrc.frc2025.subsystems.ejector.EjectorIOComp;
4646
import org.curtinfrc.frc2025.subsystems.ejector.EjectorIOSim;
4747
import org.curtinfrc.frc2025.subsystems.elevator.Elevator;
48-
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorConstants.ElevatorSetpoints;
48+
import org.curtinfrc.frc2025.subsystems.elevator.Elevator.ElevatorSetpoints;
4949
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorIO;
5050
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorIOComp;
5151
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorIOSim;

src/main/java/org/curtinfrc/frc2025/subsystems/elevator/Elevator.java

Lines changed: 44 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -1,26 +1,60 @@
11
package org.curtinfrc.frc2025.subsystems.elevator;
22

3-
import static org.curtinfrc.frc2025.subsystems.elevator.ElevatorConstants.*;
4-
53
import edu.wpi.first.math.MathUtil;
64
import edu.wpi.first.math.controller.PIDController;
75
import edu.wpi.first.math.geometry.Pose3d;
86
import edu.wpi.first.math.geometry.Rotation3d;
7+
import edu.wpi.first.util.struct.Struct;
8+
import edu.wpi.first.util.struct.StructGenerator;
9+
import edu.wpi.first.util.struct.StructSerializable;
910
import edu.wpi.first.wpilibj2.command.Command;
1011
import edu.wpi.first.wpilibj2.command.SubsystemBase;
1112
import edu.wpi.first.wpilibj2.command.button.Trigger;
1213
import java.util.function.BooleanSupplier;
1314
import java.util.function.Supplier;
14-
import org.curtinfrc.frc2025.subsystems.elevator.ElevatorConstants.ElevatorSetpoints;
1515
import org.littletonrobotics.junction.AutoLogOutput;
1616
import org.littletonrobotics.junction.Logger;
1717

1818
public class Elevator extends SubsystemBase {
19-
private static final double TOLERANCE = 0.01;
19+
private static final double TOLERANCE = 0.005;
20+
public static double CLIMB_KP = 45;
21+
public static double CLIMB_KD = 0;
22+
23+
public static enum ElevatorSetpoints implements StructSerializable {
24+
L1(0),
25+
L2(0.221),
26+
AlgaePopLow(0),
27+
L3(0.611),
28+
AlgaePopHigh(0.38),
29+
BASE(0.01),
30+
climbPrep(0.3),
31+
climbAttempt(0.5),
32+
climbed(0.01);
33+
34+
public final double setpointMetres;
35+
36+
ElevatorSetpoints(double setpointMetres) {
37+
this.setpointMetres = setpointMetres;
38+
}
39+
40+
public static ElevatorSetpoints getPopPoint(ElevatorSetpoints point) {
41+
switch (point) {
42+
case L2:
43+
return AlgaePopLow;
44+
case L3:
45+
return AlgaePopHigh;
46+
default:
47+
return BASE;
48+
}
49+
}
50+
51+
public static final Struct<ElevatorSetpoints> struct =
52+
StructGenerator.genEnum(ElevatorSetpoints.class);
53+
}
2054

2155
private final ElevatorIO io;
2256
private final ElevatorIOInputsAutoLogged inputs = new ElevatorIOInputsAutoLogged();
23-
private final PIDController climbPID = new PIDController(climbkP, climbkI, climbkD);
57+
private final PIDController climbPID = new PIDController(CLIMB_KP, 0, CLIMB_KD);
2458
private ElevatorSetpoints setpoint = ElevatorSetpoints.BASE;
2559

2660
public final Trigger isNotAtCollect = new Trigger(() -> setpoint != ElevatorSetpoints.BASE);
@@ -29,12 +63,12 @@ public class Elevator extends SubsystemBase {
2963

3064
public Elevator(ElevatorIO io) {
3165
this.io = io;
32-
climbPID.setTolerance(tolerance);
66+
climbPID.setTolerance(TOLERANCE);
3367

3468
atSetpoint =
3569
new Trigger(
3670
() -> {
37-
var error = Math.abs(inputs.positionMetres - setpoint.setpoint);
71+
var error = Math.abs(inputs.positionMetres - setpoint.setpointMetres);
3872
var velocity = Math.abs(inputs.velocityMetresPerSecond);
3973
return error < TOLERANCE && velocity < 0.1;
4074
})
@@ -62,7 +96,7 @@ public Command goToSetpoint(Supplier<ElevatorSetpoints> point, BooleanSupplier s
6296
return run(() -> {
6397
setpoint = point.get();
6498
if (safe.getAsBoolean()) {
65-
goToTarget(point.get().setpoint);
99+
goToTarget(point.get().setpointMetres);
66100
}
67101
})
68102
.withName("GoToDynamicSetpoint");
@@ -72,7 +106,7 @@ public Command goToSetpoint(ElevatorSetpoints point, BooleanSupplier safe) {
72106
return run(() -> {
73107
setpoint = point;
74108
if (safe.getAsBoolean()) {
75-
goToTarget(point.setpoint);
109+
goToTarget(point.setpointMetres);
76110
}
77111
})
78112
.withName("GoToStaticSetpoint");
@@ -82,7 +116,7 @@ public Command goToClimberSetpoint(ElevatorSetpoints point, BooleanSupplier safe
82116
return run(
83117
() -> {
84118
if (safe.getAsBoolean()) {
85-
var out = climbPID.calculate(inputs.positionMetres, point.setpoint);
119+
var out = climbPID.calculate(inputs.positionMetres, point.setpointMetres);
86120
io.setVoltage(MathUtil.clamp(out, -4, 4));
87121
}
88122
});

src/main/java/org/curtinfrc/frc2025/subsystems/elevator/ElevatorConstants.java

Lines changed: 0 additions & 51 deletions
This file was deleted.

0 commit comments

Comments
 (0)