001// Copyright (c) FIRST and other WPILib contributors.
002// Open Source Software; you can modify and/or share it under the terms of
003// the WPILib BSD license file in the root directory of this project.
004
005package edu.wpi.first.math.controller;
006
007import edu.wpi.first.math.DARE;
008import edu.wpi.first.math.MathSharedStore;
009import edu.wpi.first.math.MathUsageId;
010import edu.wpi.first.math.Matrix;
011import edu.wpi.first.math.Num;
012import edu.wpi.first.math.StateSpaceUtil;
013import edu.wpi.first.math.Vector;
014import edu.wpi.first.math.numbers.N1;
015import edu.wpi.first.math.system.Discretization;
016import edu.wpi.first.math.system.LinearSystem;
017import org.ejml.simple.SimpleMatrix;
018
019/**
020 * Contains the controller coefficients and logic for a linear-quadratic regulator (LQR). LQRs use
021 * the control law u = K(r - x).
022 *
023 * <p>For more on the underlying math, read <a
024 * href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>.
025 *
026 * @param <States> Number of states.
027 * @param <Inputs> Number of inputs.
028 * @param <Outputs> Number of outputs.
029 */
030public class LinearQuadraticRegulator<States extends Num, Inputs extends Num, Outputs extends Num> {
031  /** The current reference state. */
032  private Matrix<States, N1> m_r;
033
034  /** The computed and capped controller output. */
035  private Matrix<Inputs, N1> m_u;
036
037  // Controller gain.
038  private Matrix<Inputs, States> m_K;
039
040  /**
041   * Constructs a controller with the given coefficients and plant. Rho is defaulted to 1.
042   *
043   * <p>See <a
044   * href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
045   * for how to select the tolerances.
046   *
047   * @param plant The plant being controlled.
048   * @param qelms The maximum desired error tolerance for each state.
049   * @param relms The maximum desired control effort for each input.
050   * @param dtSeconds Discretization timestep.
051   * @throws IllegalArgumentException If the system is unstabilizable.
052   */
053  public LinearQuadraticRegulator(
054      LinearSystem<States, Inputs, Outputs> plant,
055      Vector<States> qelms,
056      Vector<Inputs> relms,
057      double dtSeconds) {
058    this(
059        plant.getA(),
060        plant.getB(),
061        StateSpaceUtil.makeCostMatrix(qelms),
062        StateSpaceUtil.makeCostMatrix(relms),
063        dtSeconds);
064  }
065
066  /**
067   * Constructs a controller with the given coefficients and plant.
068   *
069   * <p>See <a
070   * href="https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning">https://docs.wpilib.org/en/stable/docs/software/advanced-controls/state-space/state-space-intro.html#lqr-tuning</a>
071   * for how to select the tolerances.
072   *
073   * @param A Continuous system matrix of the plant being controlled.
074   * @param B Continuous input matrix of the plant being controlled.
075   * @param qelms The maximum desired error tolerance for each state.
076   * @param relms The maximum desired control effort for each input.
077   * @param dtSeconds Discretization timestep.
078   * @throws IllegalArgumentException If the system is unstabilizable.
079   */
080  public LinearQuadraticRegulator(
081      Matrix<States, States> A,
082      Matrix<States, Inputs> B,
083      Vector<States> qelms,
084      Vector<Inputs> relms,
085      double dtSeconds) {
086    this(
087        A,
088        B,
089        StateSpaceUtil.makeCostMatrix(qelms),
090        StateSpaceUtil.makeCostMatrix(relms),
091        dtSeconds);
092  }
093
094  /**
095   * Constructs a controller with the given coefficients and plant.
096   *
097   * @param A Continuous system matrix of the plant being controlled.
098   * @param B Continuous input matrix of the plant being controlled.
099   * @param Q The state cost matrix.
100   * @param R The input cost matrix.
101   * @param dtSeconds Discretization timestep.
102   * @throws IllegalArgumentException If the system is unstabilizable.
103   */
104  public LinearQuadraticRegulator(
105      Matrix<States, States> A,
106      Matrix<States, Inputs> B,
107      Matrix<States, States> Q,
108      Matrix<Inputs, Inputs> R,
109      double dtSeconds) {
110    var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
111    var discA = discABPair.getFirst();
112    var discB = discABPair.getSecond();
113
114    var S = DARE.dare(discA, discB, Q, R);
115
116    // K = (BᵀSB + R)⁻¹BᵀSA
117    m_K =
118        discB
119            .transpose()
120            .times(S)
121            .times(discB)
122            .plus(R)
123            .solve(discB.transpose().times(S).times(discA));
124
125    m_r = new Matrix<>(new SimpleMatrix(B.getNumRows(), 1));
126    m_u = new Matrix<>(new SimpleMatrix(B.getNumCols(), 1));
127
128    reset();
129    MathSharedStore.getMathShared()
130        .reportUsage(MathUsageId.kController_LinearQuadraticRegulator, 1);
131  }
132
133  /**
134   * Constructs a controller with the given coefficients and plant.
135   *
136   * @param A Continuous system matrix of the plant being controlled.
137   * @param B Continuous input matrix of the plant being controlled.
138   * @param Q The state cost matrix.
139   * @param R The input cost matrix.
140   * @param N The state-input cross-term cost matrix.
141   * @param dtSeconds Discretization timestep.
142   * @throws IllegalArgumentException If the system is unstabilizable.
143   */
144  public LinearQuadraticRegulator(
145      Matrix<States, States> A,
146      Matrix<States, Inputs> B,
147      Matrix<States, States> Q,
148      Matrix<Inputs, Inputs> R,
149      Matrix<States, Inputs> N,
150      double dtSeconds) {
151    var discABPair = Discretization.discretizeAB(A, B, dtSeconds);
152    var discA = discABPair.getFirst();
153    var discB = discABPair.getSecond();
154
155    var S = DARE.dare(discA, discB, Q, R, N);
156
157    // K = (BᵀSB + R)⁻¹(BᵀSA + Nᵀ)
158    m_K =
159        discB
160            .transpose()
161            .times(S)
162            .times(discB)
163            .plus(R)
164            .solve(discB.transpose().times(S).times(discA).plus(N.transpose()));
165
166    m_r = new Matrix<>(new SimpleMatrix(B.getNumRows(), 1));
167    m_u = new Matrix<>(new SimpleMatrix(B.getNumCols(), 1));
168
169    reset();
170    MathSharedStore.getMathShared()
171        .reportUsage(MathUsageId.kController_LinearQuadraticRegulator, 1);
172  }
173
174  /**
175   * Returns the control input vector u.
176   *
177   * @return The control input.
178   */
179  public Matrix<Inputs, N1> getU() {
180    return m_u;
181  }
182
183  /**
184   * Returns an element of the control input vector u.
185   *
186   * @param row Row of u.
187   * @return The row of the control input vector.
188   */
189  public double getU(int row) {
190    return m_u.get(row, 0);
191  }
192
193  /**
194   * Returns the reference vector r.
195   *
196   * @return The reference vector.
197   */
198  public Matrix<States, N1> getR() {
199    return m_r;
200  }
201
202  /**
203   * Returns an element of the reference vector r.
204   *
205   * @param row Row of r.
206   * @return The row of the reference vector.
207   */
208  public double getR(int row) {
209    return m_r.get(row, 0);
210  }
211
212  /**
213   * Returns the controller matrix K.
214   *
215   * @return the controller matrix K.
216   */
217  public Matrix<Inputs, States> getK() {
218    return m_K;
219  }
220
221  /** Resets the controller. */
222  public final void reset() {
223    m_r.fill(0.0);
224    m_u.fill(0.0);
225  }
226
227  /**
228   * Returns the next output of the controller.
229   *
230   * @param x The current state x.
231   * @return The next controller output.
232   */
233  public Matrix<Inputs, N1> calculate(Matrix<States, N1> x) {
234    m_u = m_K.times(m_r.minus(x));
235    return m_u;
236  }
237
238  /**
239   * Returns the next output of the controller.
240   *
241   * @param x The current state x.
242   * @param nextR the next reference vector r.
243   * @return The next controller output.
244   */
245  public Matrix<Inputs, N1> calculate(Matrix<States, N1> x, Matrix<States, N1> nextR) {
246    m_r = nextR;
247    return calculate(x);
248  }
249
250  /**
251   * Adjusts LQR controller gain to compensate for a pure time delay in the input.
252   *
253   * <p>Linear-Quadratic regulator controller gains tend to be aggressive. If sensor measurements
254   * are time-delayed too long, the LQR may be unstable. However, if we know the amount of delay, we
255   * can compute the control based on where the system will be after the time delay.
256   *
257   * <p>See <a
258   * href="https://file.tavsys.net/control/controls-engineering-in-frc.pdf">https://file.tavsys.net/control/controls-engineering-in-frc.pdf</a>
259   * appendix C.4 for a derivation.
260   *
261   * @param plant The plant being controlled.
262   * @param dtSeconds Discretization timestep in seconds.
263   * @param inputDelaySeconds Input time delay in seconds.
264   */
265  public void latencyCompensate(
266      LinearSystem<States, Inputs, Outputs> plant, double dtSeconds, double inputDelaySeconds) {
267    var discABPair = Discretization.discretizeAB(plant.getA(), plant.getB(), dtSeconds);
268    var discA = discABPair.getFirst();
269    var discB = discABPair.getSecond();
270
271    m_K = m_K.times((discA.minus(discB.times(m_K))).pow(inputDelaySeconds / dtSeconds));
272  }
273}