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