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.wpilibj.simulation;
006
007import edu.wpi.first.math.Matrix;
008import edu.wpi.first.math.Num;
009import edu.wpi.first.math.StateSpaceUtil;
010import edu.wpi.first.math.numbers.N1;
011import edu.wpi.first.math.system.LinearSystem;
012import org.ejml.MatrixDimensionException;
013import org.ejml.simple.SimpleMatrix;
014
015/**
016 * This class helps simulate linear systems. To use this class, do the following in the {@link
017 * edu.wpi.first.wpilibj.IterativeRobotBase#simulationPeriodic} method.
018 *
019 * <p>Call {@link #setInput(double...)} with the inputs to the system (usually voltage).
020 *
021 * <p>Call {@link #update} to update the simulation.
022 *
023 * <p>Set simulated sensor readings with the simulated positions in {@link #getOutput()}
024 *
025 * @param <States> Number of states of the system.
026 * @param <Inputs> Number of inputs to the system.
027 * @param <Outputs> Number of outputs of the system.
028 */
029public class LinearSystemSim<States extends Num, Inputs extends Num, Outputs extends Num> {
030  /** The plant that represents the linear system. */
031  protected final LinearSystem<States, Inputs, Outputs> m_plant;
032
033  /** State vector. */
034  protected Matrix<States, N1> m_x;
035
036  /** Input vector. */
037  protected Matrix<Inputs, N1> m_u;
038
039  /** Output vector. */
040  protected Matrix<Outputs, N1> m_y;
041
042  /** The standard deviations of measurements, used for adding noise to the measurements. */
043  protected final Matrix<Outputs, N1> m_measurementStdDevs;
044
045  /**
046   * Creates a simulated generic linear system with measurement noise.
047   *
048   * @param system The system being controlled.
049   * @param measurementStdDevs Standard deviations of measurements. Can be empty if no noise is
050   *     desired. If present must have same number of items as Outputs
051   */
052  public LinearSystemSim(
053      LinearSystem<States, Inputs, Outputs> system, double... measurementStdDevs) {
054    if (measurementStdDevs.length != 0 && measurementStdDevs.length != system.getC().getNumRows()) {
055      throw new MatrixDimensionException(
056          "Malformed measurementStdDevs! Got "
057              + measurementStdDevs.length
058              + " elements instead of "
059              + system.getC().getNumRows());
060    }
061    this.m_plant = system;
062    if (measurementStdDevs.length == 0) {
063      m_measurementStdDevs = new Matrix<>(new SimpleMatrix(system.getC().getNumRows(), 1));
064    } else {
065      m_measurementStdDevs = new Matrix<>(new SimpleMatrix(measurementStdDevs));
066    }
067    m_x = new Matrix<>(new SimpleMatrix(system.getA().getNumRows(), 1));
068    m_u = new Matrix<>(new SimpleMatrix(system.getB().getNumCols(), 1));
069    m_y = new Matrix<>(new SimpleMatrix(system.getC().getNumRows(), 1));
070  }
071
072  /**
073   * Updates the simulation.
074   *
075   * @param dtSeconds The time between updates.
076   */
077  public void update(double dtSeconds) {
078    // Update X. By default, this is the linear system dynamics X = Ax + Bu
079    m_x = updateX(m_x, m_u, dtSeconds);
080
081    // y = cx + du
082    m_y = m_plant.calculateY(m_x, m_u);
083
084    // Add measurement noise.
085    if (m_measurementStdDevs != null) {
086      m_y = m_y.plus(StateSpaceUtil.makeWhiteNoiseVector(m_measurementStdDevs));
087    }
088  }
089
090  /**
091   * Returns the current output of the plant.
092   *
093   * @return The current output of the plant.
094   */
095  public Matrix<Outputs, N1> getOutput() {
096    return m_y;
097  }
098
099  /**
100   * Returns an element of the current output of the plant.
101   *
102   * @param row The row to return.
103   * @return An element of the current output of the plant.
104   */
105  public double getOutput(int row) {
106    return m_y.get(row, 0);
107  }
108
109  /**
110   * Sets the system inputs (usually voltages).
111   *
112   * @param u The system inputs.
113   */
114  public void setInput(Matrix<Inputs, N1> u) {
115    this.m_u = u;
116  }
117
118  /**
119   * Sets the system inputs.
120   *
121   * @param row The row in the input matrix to set.
122   * @param value The value to set the row to.
123   */
124  public void setInput(int row, double value) {
125    m_u.set(row, 0, value);
126  }
127
128  /**
129   * Sets the system inputs.
130   *
131   * @param u An array of doubles that represent the inputs of the system.
132   */
133  public void setInput(double... u) {
134    if (u.length != m_u.getNumRows()) {
135      throw new MatrixDimensionException(
136          "Malformed input! Got " + u.length + " elements instead of " + m_u.getNumRows());
137    }
138    m_u = new Matrix<>(new SimpleMatrix(m_u.getNumRows(), 1, true, u));
139  }
140
141  /**
142   * Returns the current input of the plant.
143   *
144   * @return The current input of the plant.
145   */
146  public Matrix<Inputs, N1> getInput() {
147    return m_u;
148  }
149
150  /**
151   * Returns an element of the current input of the plant.
152   *
153   * @param row The row to return.
154   * @return An element of the current input of the plant.
155   */
156  public double getInput(int row) {
157    return m_u.get(row, 0);
158  }
159
160  /**
161   * Sets the system state.
162   *
163   * @param state The new state.
164   */
165  public void setState(Matrix<States, N1> state) {
166    m_x = state;
167  }
168
169  /**
170   * Updates the state estimate of the system.
171   *
172   * @param currentXhat The current state estimate.
173   * @param u The system inputs (usually voltage).
174   * @param dtSeconds The time difference between controller updates.
175   * @return The new state.
176   */
177  protected Matrix<States, N1> updateX(
178      Matrix<States, N1> currentXhat, Matrix<Inputs, N1> u, double dtSeconds) {
179    return m_plant.calculateX(currentXhat, u, dtSeconds);
180  }
181
182  /**
183   * Clamp the input vector such that no element exceeds the maximum allowed value. If any does, the
184   * relative magnitudes of the input will be maintained.
185   *
186   * @param maxInput The maximum magnitude of the input vector after clamping.
187   */
188  protected void clampInput(double maxInput) {
189    m_u = StateSpaceUtil.desaturateInputVector(m_u, maxInput);
190  }
191}