|
| 1 | +package org.curtinfrc.frc2025.util; |
| 2 | + |
| 3 | +import edu.wpi.first.math.VecBuilder; |
| 4 | +import edu.wpi.first.math.controller.LinearQuadraticRegulator; |
| 5 | +import edu.wpi.first.math.numbers.N1; |
| 6 | +import edu.wpi.first.math.numbers.N2; |
| 7 | +import edu.wpi.first.math.system.LinearSystem; |
| 8 | + |
| 9 | +/** A calculator for generating optimal feedback gains given known control characteristics. */ |
| 10 | +public class FeedbackAnalysis { |
| 11 | + public record FeedbackGains(double kP, double kD) {} |
| 12 | + |
| 13 | + /** |
| 14 | + * Calculates optimal PD gains for a second-order position system. |
| 15 | + * |
| 16 | + * @param system The dynamics function for the system. |
| 17 | + * @param maxControlEffort Max control effort for the controller. |
| 18 | + * @param positionTolerance Max position tolerance for the controller. |
| 19 | + * @param velocityTolerance Max velocity tolerance for the controller. |
| 20 | + * @param controllerPeriodSeconds Period of the controller. |
| 21 | + * @param measurementDelaySeconds Measurement delay. |
| 22 | + * @return Optimal PD gains given the above system and control characteristics. |
| 23 | + * @see edu.wpi.first.math.system.plant.LinearSystemId |
| 24 | + */ |
| 25 | + public static FeedbackGains getPositionGains( |
| 26 | + LinearSystem<N2, N1, N2> system, |
| 27 | + double maxControlEffort, |
| 28 | + double positionTolerance, |
| 29 | + double velocityTolerance, |
| 30 | + double controllerPeriodSeconds, |
| 31 | + double measurementDelaySeconds) { |
| 32 | + // Create an LQR with 2 states to control -- position and velocity. |
| 33 | + var controller = |
| 34 | + new LinearQuadraticRegulator<>( |
| 35 | + system, |
| 36 | + VecBuilder.fill(positionTolerance, velocityTolerance), |
| 37 | + VecBuilder.fill(maxControlEffort), |
| 38 | + controllerPeriodSeconds); |
| 39 | + // Compensate for any latency from sensor measurements, filtering, etc. |
| 40 | + controller.latencyCompensate(system, controllerPeriodSeconds, measurementDelaySeconds); |
| 41 | + |
| 42 | + return new FeedbackGains(controller.getK().get(0, 0), controller.getK().get(0, 1)); |
| 43 | + } |
| 44 | + |
| 45 | + /** |
| 46 | + * Calculates an optimal P gain for a first-order velocity system. |
| 47 | + * |
| 48 | + * @param system The dynamics function for the system. |
| 49 | + * @param maxControlEffort Max control effort for the controller. |
| 50 | + * @param tolerance Max velocity tolerance for the controller. |
| 51 | + * @param controllerPeriodSeconds Period of the controller. |
| 52 | + * @param measurementDelaySeconds Measurement delay. |
| 53 | + * @return Optimal P gain given the above system and control characteristics. |
| 54 | + * @see edu.wpi.first.math.system.plant.LinearSystemId |
| 55 | + */ |
| 56 | + public static double getVelocityPGain( |
| 57 | + LinearSystem<N1, N1, N1> system, |
| 58 | + double maxControlEffort, |
| 59 | + double tolerance, |
| 60 | + double controllerPeriodSeconds, |
| 61 | + double measurementDelaySeconds) { |
| 62 | + // Create an LQR controller with 1 state -- velocity. |
| 63 | + var controller = |
| 64 | + new LinearQuadraticRegulator<>( |
| 65 | + system, |
| 66 | + VecBuilder.fill(tolerance), |
| 67 | + VecBuilder.fill(maxControlEffort), |
| 68 | + controllerPeriodSeconds); |
| 69 | + // Compensate for any latency from sensor measurements, filtering, etc. |
| 70 | + controller.latencyCompensate(system, controllerPeriodSeconds, measurementDelaySeconds); |
| 71 | + |
| 72 | + return controller.getK().get(0, 0); |
| 73 | + } |
| 74 | +} |
0 commit comments