Skip to content

Commit 8a69d0e

Browse files
committed
refactor: store elevator CAN constants in subsystem class
Signed-off-by: Dasun Abeykoon <[email protected]>
1 parent 9335cd8 commit 8a69d0e

File tree

2 files changed

+21
-13
lines changed

2 files changed

+21
-13
lines changed

src/main/java/org/frc6423/robot/subsystems/superstructure/elevator/Elevator.java

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,15 @@
3131
import edu.wpi.first.wpilibj2.command.Command;
3232
import edu.wpi.first.wpilibj2.command.SubsystemBase;
3333
import java.util.function.DoubleSupplier;
34-
import org.frc6423.robot.Constants;
3534
import org.frc6423.robot.Robot;
3635

3736
/** Elevator Subsystem */
3837
public class Elevator extends SubsystemBase implements AutoCloseable {
3938
// * CONSTANTS
39+
public static final String CANBUS = "CANCHAN";
40+
public static final int PARENT_MOTOR_ID = 14;
41+
public static final int CHILD_MOTOR_ID = 15;
42+
4043
/** Gear ratio of the elevator gearbox */
4144
public static final double GEAR_REDUCTION = 3 / 1;
4245

@@ -83,23 +86,26 @@ public class Elevator extends SubsystemBase implements AutoCloseable {
8386
mech2d.getRoot("carriageRoot", (MAX_EXTENSION_HEIGHT.in(Centimeters) / 2) - 2, 0.0);
8487

8588
/**
86-
* @return {@link Elevator} subsystem with no hardware
89+
* @return fake {@link Elevator} subsystem
8790
*/
8891
public static Elevator none() {
89-
return new Elevator(new ElevatorIONone());
92+
if (Robot.isReal()) {
93+
return new Elevator(new ElevatorIOReal());
94+
} else {
95+
return new Elevator(new ElevatorIOSim());
96+
}
9097
}
9198

9299
/**
93-
* Factory to create {@link Elevator} subsystem based on whether the robot is simulated or not
100+
* Factory for creating a {@link Elevator} subsystem
94101
*
95-
* @return {@link Elevator} subsystem
102+
* @return {@link Elevator} Subsystem
96103
*/
97104
public static Elevator create() {
98-
if (Robot.isSimulation()) {
99-
return new Elevator(new ElevatorIOSim());
105+
if (Robot.isReal()) {
106+
return new Elevator(new ElevatorIOReal());
100107
} else {
101-
return new Elevator(
102-
new ElevatorIOReal(Constants.Ports.ELEVATOR_PARENT, Constants.Ports.ELEVATOR_CHILD));
108+
return new Elevator(new ElevatorIOSim());
103109
}
104110
}
105111

src/main/java/org/frc6423/robot/subsystems/superstructure/elevator/ElevatorIOReal.java

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,11 @@
88

99
import static edu.wpi.first.units.Units.MetersPerSecond;
1010
import static edu.wpi.first.units.Units.MetersPerSecondPerSecond;
11+
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.CANBUS;
12+
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.CHILD_MOTOR_ID;
1113
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.MAX_ACCELERATION;
1214
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.MAX_VELOCITY;
15+
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.PARENT_MOTOR_ID;
1316
import static org.frc6423.robot.subsystems.superstructure.elevator.Elevator.SENSOR_TO_MECH_RATIO;
1417

1518
import com.ctre.phoenix6.BaseStatusSignal;
@@ -21,7 +24,6 @@
2124
import com.ctre.phoenix6.signals.GravityTypeValue;
2225
import com.ctre.phoenix6.signals.InvertedValue;
2326
import com.ctre.phoenix6.signals.NeutralModeValue;
24-
import org.frc6423.lib.types.CanDeviceId;
2527

2628
/** Comp bot {@link ElevatorIO} */
2729
public class ElevatorIOReal implements ElevatorIO {
@@ -35,9 +37,9 @@ public class ElevatorIOReal implements ElevatorIO {
3537
private final BaseStatusSignal parentPoseSig, parentCurrentSig, parentTempSig;
3638
private final BaseStatusSignal childPoseSig, childCurrentSig, childTempSig;
3739

38-
public ElevatorIOReal(CanDeviceId parentMotorId, CanDeviceId childMotorId) {
39-
parent = new TalonFX(parentMotorId.getCanId(), parentMotorId.getBusName());
40-
child = new TalonFX(childMotorId.getCanId(), childMotorId.getBusName());
40+
public ElevatorIOReal() {
41+
parent = new TalonFX(PARENT_MOTOR_ID, CANBUS);
42+
child = new TalonFX(CHILD_MOTOR_ID, CANBUS);
4143

4244
conf = new TalonFXConfiguration();
4345

0 commit comments

Comments
 (0)