diff --git a/src/main/java/frc/robot/PIDConstants.java b/src/main/java/frc/robot/PIDConstants.java new file mode 100644 index 0000000..de08f22 --- /dev/null +++ b/src/main/java/frc/robot/PIDConstants.java @@ -0,0 +1,36 @@ +package frc.robot; + +public final class PIDConstants { + public static final class balancePID { + // Balance PID / AutoBalance + public static final double balance_P = 0.0625; // 1/16 + public static final double balance_I = 0.00; + public static final double balance_D = 0.00; + public static final double MaxBalanceRateDegPerS = 10; + public static final double MaxBalanceAccelerationDegPerSSquared = 20; + public static final double BalanceToleranceDeg = 2; // max diff in degrees + } + + public static final class distancePID { + // Distance PID / MoveDistance + public static final double distance_P = 0.1; + public static final double distance_I = 0.00; + public static final double distance_D = 0.00; + public static final double distanceMaxSpeed = 1; // m/s + public static final double distanceMaxAcceleration = 2; // m/s^2 + public static final double DistanceTolerance = 0.01; // max diff in meters + public static final double DistanceSpeedTolerance = 0.1; // ignore if velocity is below. (m) + } + + public static final class turnPID { + // Angle PID / RotateToAngle + public static final double turn_P = 0.1; + public static final double turn_I = 0.00; + public static final double turn_D = 0.00; + public static final double MaxTurnRateDegPerS = 100; + public static final double MaxTurnAccelerationDegPerSSquared = 50; + public static final double TurnToleranceDeg = 3; // max diff in degrees + public static final double TurnRateToleranceDegPerS = 10; // degrees per second + // false when inactive, true when active / a target is set. + } +} diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java index 5d9d4f2..9e98b51 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -46,62 +46,43 @@ public class DriveSubsystem extends SubsystemBase { // Odometry class for tracking robot pose (position on field) private final DifferentialDriveOdometry m_driveOdometry; - // Angle PID / RotateToAngle - static final double turn_P = 0.1; - static final double turn_I = 0.00; - static final double turn_D = 0.00; - static final double MaxTurnRateDegPerS = 100; - static final double MaxTurnAccelerationDegPerSSquared = 300; - static final double TurnToleranceDeg = 3; // max diff in degrees - static final double TurnRateToleranceDegPerS = 10; // degrees per second - // false when inactive, true when active / a target is set. private boolean turnControllerEnabled = false; private double turnRotateToAngleRate; // This value will be updated by the PID Controller // pid controller for "RotateToAngle" private final ProfiledPIDController m_turnController = new ProfiledPIDController( - turn_P, - turn_I, - turn_D, - new TrapezoidProfile.Constraints(MaxTurnRateDegPerS, MaxTurnAccelerationDegPerSSquared)); - - // Distance PID / MoveDistance - static final double distance_P = 0.1; - static final double distance_I = 0.00; - static final double distance_D = 0.00; - static final double distanceMaxSpeed = 1; // m/s - static final double distanceMaxAcceleration = 2; // m/s^2 - static final double DistanceTolerance = 0.01; // max diff in meters - static final double DistanceSpeedTolerance = 0.1; // ignore if velocity is below. (m) + frc.robot.PIDConstants.turnPID.turn_P, + frc.robot.PIDConstants.turnPID.turn_I, + frc.robot.PIDConstants.turnPID.turn_D, + new TrapezoidProfile.Constraints( + frc.robot.PIDConstants.turnPID.MaxTurnRateDegPerS, + frc.robot.PIDConstants.turnPID.MaxTurnAccelerationDegPerSSquared)); + // false when inactive, true when active / a target is set. private boolean distanceControllerEnabled = false; private double distanceThrottleRate; // This value will be updated by the PID Controller // pid controller for "MoveDistance" private final ProfiledPIDController m_distanceController = new ProfiledPIDController( - distance_P, - distance_I, - distance_D, - new TrapezoidProfile.Constraints(distanceMaxSpeed, distanceMaxAcceleration)); - - // Balance PID / AutoBalance - static final double balance_P = 0.0625; // 1/16 - static final double balance_I = 0.00; - static final double balance_D = 0.00; - static final double MaxBalanceRateDegPerS = 10; - static final double MaxBalanceAccelerationDegPerSSquared = 20; - static final double BalanceToleranceDeg = 2; // max diff in degrees + frc.robot.PIDConstants.distancePID.distance_P, + frc.robot.PIDConstants.distancePID.distance_I, + frc.robot.PIDConstants.distancePID.distance_D, + new TrapezoidProfile.Constraints( + frc.robot.PIDConstants.distancePID.distanceMaxSpeed, + frc.robot.PIDConstants.distancePID.distanceMaxAcceleration)); + // false when inactive, true when active / a target is set. private boolean balanceControllerEnabled = false; private double balanceThrottleRate; // This value will be updated by the PID Controller // pid controller for balanceCorrection private final ProfiledPIDController m_balanceController = new ProfiledPIDController( - balance_P, - balance_I, - balance_D, + frc.robot.PIDConstants.balancePID.balance_P, + frc.robot.PIDConstants.balancePID.balance_I, + frc.robot.PIDConstants.balancePID.balance_D, new TrapezoidProfile.Constraints( - MaxBalanceRateDegPerS, MaxBalanceAccelerationDegPerSSquared)); + frc.robot.PIDConstants.balancePID.MaxBalanceRateDegPerS, + frc.robot.PIDConstants.balancePID.MaxBalanceAccelerationDegPerSSquared)); /** Creates a new DriveSubsystem. */ public DriveSubsystem() { @@ -145,12 +126,17 @@ public DriveSubsystem() { // config turn pid controller. m_turnController.enableContinuousInput(-180.0f, 180.0f); - m_turnController.setTolerance(TurnToleranceDeg, TurnRateToleranceDegPerS); + m_turnController.setTolerance( + frc.robot.PIDConstants.turnPID.TurnToleranceDeg, + frc.robot.PIDConstants.turnPID.TurnRateToleranceDegPerS); // config distance pid controller - m_distanceController.setTolerance(DistanceTolerance, DistanceSpeedTolerance); + m_distanceController.setTolerance( + frc.robot.PIDConstants.distancePID.DistanceTolerance, + frc.robot.PIDConstants.distancePID.DistanceSpeedTolerance); // this is the target pitch/ tilt error. m_balanceController.setGoal(0); - m_balanceController.setTolerance(BalanceToleranceDeg); // max error in degrees + m_balanceController.setTolerance( + frc.robot.PIDConstants.balancePID.BalanceToleranceDeg); // max error in degrees } /**