Skip to content

Commit

Permalink
cleaning up config values
Browse files Browse the repository at this point in the history
  • Loading branch information
chrishoffman committed Jan 30, 2025
1 parent a3d6e73 commit c3bd4e7
Show file tree
Hide file tree
Showing 5 changed files with 37 additions and 54 deletions.
39 changes: 24 additions & 15 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -142,27 +142,36 @@ public static final class SwerveDriveConfig {
}

/**
* Configurations for the elevator.
* Configurations for the coraller.
*/
public static final class ElevatorConfig {
public static final class CorallerConfig {
// Angler
public static final double kAnglerP = 0.0;
public static final double kAnglerI = 0.0;
public static final double kAnglerD = 0.0;
public static final double kAnglerEncoderPositionConversionFactor = 1;
public static final double kAnglerEncoderVelocityConversionFactor = kAnglerEncoderPositionConversionFactor / 60.0;

// Elevator
public static final double kElevatorP = 0.0;
public static final double kElevatorI = 0.0;
public static final double kElevatorD = 0.0;
public static final double kElevatorEncoderPositionConversionFactor = 1;
public static final double kElevatorEncoderVelocityConversionFactor = kElevatorEncoderPositionConversionFactor
/ 60.0;
public static final double kElevatorEncoderVelocityConversionFactor = kElevatorEncoderPositionConversionFactor / 60.0;
public static final double kRobotElevatorStowHeightInches = 48;
}

/**
* Configurations for the coraller.
*/
public static final class CorallerConfig {
public static final double kCorallerP = 0.0;
public static final double kCorallerI = 0.0;
public static final double kCorallerD = 0.0;
public static final double kCorallerEncoderPositionConversionFactor = 1;
public static final double kCorallerEncoderVelocityConversionFactor = kCorallerEncoderPositionConversionFactor
/ 60.0;
// Coraller Configuration
public static final double STOW_ANGLE = 0;
public static final double STOW_HEIGHT = 0;
public static final double L1_ANGLE = 0;
public static final double L1_HEIGHT = 0;
public static final double L2_ANGLE = 0;
public static final double L2_HEIGHT = 0;
public static final double L3_ANGLE = 0;
public static final double L3_HEIGHT = 0;
public static final double L4_ANGLE = 0;
public static final double L4_HEIGHT = 0;
public static final double RECEIVE_ANGLE = 0;
public static final double RECEIVE_HEIGHT = 0;
}
}
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/coraller/Angler.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ public class Angler {

public Angler() {
var anglerClosedLoopConfig = new ClosedLoopConfig()
.pid(CorallerConfig.kCorallerP, CorallerConfig.kCorallerI, CorallerConfig.kCorallerD,
.pid(CorallerConfig.kAnglerP, CorallerConfig.kAnglerI, CorallerConfig.kAnglerD,
ClosedLoopSlot.kSlot0);
var anglerConfig = new SparkMaxConfig()
.idleMode(IdleMode.kBrake)
Expand Down
16 changes: 8 additions & 8 deletions src/main/java/frc/robot/subsystems/coraller/Coraller.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,16 +3,16 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.ElevatorConfig;
import frc.robot.Constants.CorallerConfig;

public class Coraller extends SubsystemBase {
public enum Configuration {
STOW(CorallerConstants.STOW_HEIGHT, CorallerConstants.STOW_ANGLE),
L1(CorallerConstants.L1_HEIGHT, CorallerConstants.L1_ANGLE),
L2(CorallerConstants.L2_HEIGHT, CorallerConstants.L2_ANGLE),
L3(CorallerConstants.L3_HEIGHT, CorallerConstants.L3_ANGLE),
L4(CorallerConstants.L4_HEIGHT, CorallerConstants.L4_ANGLE),
RECEIVE(CorallerConstants.RECEIVE_HEIGHT, CorallerConstants.RECEIVE_ANGLE);
STOW(CorallerConfig.STOW_HEIGHT, CorallerConfig.STOW_ANGLE),
L1(CorallerConfig.L1_HEIGHT, CorallerConfig.L1_ANGLE),
L2(CorallerConfig.L2_HEIGHT, CorallerConfig.L2_ANGLE),
L3(CorallerConfig.L3_HEIGHT, CorallerConfig.L3_ANGLE),
L4(CorallerConfig.L4_HEIGHT, CorallerConfig.L4_ANGLE),
RECEIVE(CorallerConfig.RECEIVE_HEIGHT, CorallerConfig.RECEIVE_ANGLE);

private final double elevatorPosition;
private final double anglerPosition;
Expand All @@ -28,7 +28,7 @@ private Configuration(double elevatorPosition, double anglerPosition) {
private final Intake intake;

public Coraller() {
elevator = new Elevator(ElevatorConfig.kRobotElevatorStowHeightInches);
elevator = new Elevator(CorallerConfig.kRobotElevatorStowHeightInches);
angler = new Angler();
intake = new Intake();
}
Expand Down
26 changes: 0 additions & 26 deletions src/main/java/frc/robot/subsystems/coraller/CorallerConstants.java

This file was deleted.

8 changes: 4 additions & 4 deletions src/main/java/frc/robot/subsystems/coraller/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import com.revrobotics.spark.config.SparkMaxConfig;

import frc.robot.RobotMap;
import frc.robot.Constants.ElevatorConfig;
import frc.robot.Constants.CorallerConfig;

public class Elevator {
private final SparkMax motor;
Expand All @@ -25,10 +25,10 @@ public class Elevator {

public Elevator(double base) {
var elevatorEncoderConfig = new EncoderConfig()
.positionConversionFactor(ElevatorConfig.kElevatorEncoderPositionConversionFactor)
.velocityConversionFactor(ElevatorConfig.kElevatorEncoderVelocityConversionFactor);
.positionConversionFactor(CorallerConfig.kElevatorEncoderPositionConversionFactor)
.velocityConversionFactor(CorallerConfig.kElevatorEncoderVelocityConversionFactor);
var elevatorClosedLoopConfig = new ClosedLoopConfig()
.pid(ElevatorConfig.kElevatorP, ElevatorConfig.kElevatorI, ElevatorConfig.kElevatorD, ClosedLoopSlot.kSlot0);
.pid(CorallerConfig.kElevatorP, CorallerConfig.kElevatorI, CorallerConfig.kElevatorD, ClosedLoopSlot.kSlot0);
var elevatorConfig = new SparkMaxConfig()
.idleMode(IdleMode.kBrake)
.smartCurrentLimit(45)
Expand Down

0 comments on commit c3bd4e7

Please sign in to comment.