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