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.MathUtil;
008import edu.wpi.first.math.Matrix;
009import edu.wpi.first.math.VecBuilder;
010import edu.wpi.first.math.numbers.N1;
011import edu.wpi.first.math.numbers.N2;
012import edu.wpi.first.math.system.LinearSystem;
013import edu.wpi.first.math.system.NumericalIntegration;
014import edu.wpi.first.math.system.plant.DCMotor;
015import edu.wpi.first.math.system.plant.LinearSystemId;
016import edu.wpi.first.wpilibj.RobotController;
017
018/** Represents a simulated single jointed arm mechanism. */
019public class SingleJointedArmSim extends LinearSystemSim<N2, N1, N2> {
020  // The gearbox for the arm.
021  private final DCMotor m_gearbox;
022
023  // The gearing between the motors and the output.
024  private final double m_gearing;
025
026  // The length of the arm.
027  private final double m_armLenMeters;
028
029  // The minimum angle that the arm is capable of.
030  private final double m_minAngle;
031
032  // The maximum angle that the arm is capable of.
033  private final double m_maxAngle;
034
035  // Whether the simulator should simulate gravity.
036  private final boolean m_simulateGravity;
037
038  /**
039   * Creates a simulated arm mechanism.
040   *
041   * @param plant The linear system that represents the arm. This system can be created with {@link
042   *     edu.wpi.first.math.system.plant.LinearSystemId#createSingleJointedArmSystem(DCMotor,
043   *     double, double)}.
044   * @param gearbox The type of and number of motors in the arm gearbox.
045   * @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
046   * @param armLengthMeters The length of the arm.
047   * @param minAngleRads The minimum angle that the arm is capable of, with 0 radians being
048   *     horizontal.
049   * @param maxAngleRads The maximum angle that the arm is capable of, with 0 radians being
050   *     horizontal.
051   * @param simulateGravity Whether gravity should be simulated or not.
052   * @param startingAngleRads The initial position of the Arm simulation in radians, with 0 radians
053   *     being horizontal.
054   * @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
055   *     noise is desired. If present must have 1 element for position.
056   */
057  @SuppressWarnings("this-escape")
058  public SingleJointedArmSim(
059      LinearSystem<N2, N1, N2> plant,
060      DCMotor gearbox,
061      double gearing,
062      double armLengthMeters,
063      double minAngleRads,
064      double maxAngleRads,
065      boolean simulateGravity,
066      double startingAngleRads,
067      double... measurementStdDevs) {
068    super(plant, measurementStdDevs);
069    m_gearbox = gearbox;
070    m_gearing = gearing;
071    m_armLenMeters = armLengthMeters;
072    m_minAngle = minAngleRads;
073    m_maxAngle = maxAngleRads;
074    m_simulateGravity = simulateGravity;
075
076    setState(startingAngleRads, 0.0);
077  }
078
079  /**
080   * Creates a simulated arm mechanism.
081   *
082   * @param gearbox The type of and number of motors in the arm gearbox.
083   * @param gearing The gearing of the arm (numbers greater than 1 represent reductions).
084   * @param jKgMetersSquared The moment of inertia of the arm; can be calculated from CAD software.
085   * @param armLengthMeters The length of the arm.
086   * @param minAngleRads The minimum angle that the arm is capable of, with 0 radians being
087   *     horizontal.
088   * @param maxAngleRads The maximum angle that the arm is capable of, with 0 radians being
089   *     horizontal.
090   * @param simulateGravity Whether gravity should be simulated or not.
091   * @param startingAngleRads The initial position of the Arm simulation in radians, with 0 radians
092   *     being horizontal.
093   * @param measurementStdDevs The standard deviations of the measurements. Can be omitted if no
094   *     noise is desired. If present must have 1 element for position.
095   */
096  public SingleJointedArmSim(
097      DCMotor gearbox,
098      double gearing,
099      double jKgMetersSquared,
100      double armLengthMeters,
101      double minAngleRads,
102      double maxAngleRads,
103      boolean simulateGravity,
104      double startingAngleRads,
105      double... measurementStdDevs) {
106    this(
107        LinearSystemId.createSingleJointedArmSystem(gearbox, jKgMetersSquared, gearing),
108        gearbox,
109        gearing,
110        armLengthMeters,
111        minAngleRads,
112        maxAngleRads,
113        simulateGravity,
114        startingAngleRads,
115        measurementStdDevs);
116  }
117
118  /**
119   * Sets the arm's state. The new angle will be limited between the minimum and maximum allowed
120   * limits.
121   *
122   * @param angleRadians The new angle in radians.
123   * @param velocityRadPerSec The new angular velocity in radians per second.
124   */
125  public final void setState(double angleRadians, double velocityRadPerSec) {
126    setState(
127        VecBuilder.fill(MathUtil.clamp(angleRadians, m_minAngle, m_maxAngle), velocityRadPerSec));
128  }
129
130  /**
131   * Returns whether the arm would hit the lower limit.
132   *
133   * @param currentAngleRads The current arm height.
134   * @return Whether the arm would hit the lower limit.
135   */
136  public boolean wouldHitLowerLimit(double currentAngleRads) {
137    return currentAngleRads <= this.m_minAngle;
138  }
139
140  /**
141   * Returns whether the arm would hit the upper limit.
142   *
143   * @param currentAngleRads The current arm height.
144   * @return Whether the arm would hit the upper limit.
145   */
146  public boolean wouldHitUpperLimit(double currentAngleRads) {
147    return currentAngleRads >= this.m_maxAngle;
148  }
149
150  /**
151   * Returns whether the arm has hit the lower limit.
152   *
153   * @return Whether the arm has hit the lower limit.
154   */
155  public boolean hasHitLowerLimit() {
156    return wouldHitLowerLimit(getAngleRads());
157  }
158
159  /**
160   * Returns whether the arm has hit the upper limit.
161   *
162   * @return Whether the arm has hit the upper limit.
163   */
164  public boolean hasHitUpperLimit() {
165    return wouldHitUpperLimit(getAngleRads());
166  }
167
168  /**
169   * Returns the current arm angle.
170   *
171   * @return The current arm angle.
172   */
173  public double getAngleRads() {
174    return getOutput(0);
175  }
176
177  /**
178   * Returns the current arm velocity.
179   *
180   * @return The current arm velocity.
181   */
182  public double getVelocityRadPerSec() {
183    return getOutput(1);
184  }
185
186  /**
187   * Returns the arm current draw.
188   *
189   * @return The arm current draw.
190   */
191  public double getCurrentDrawAmps() {
192    // Reductions are greater than 1, so a reduction of 10:1 would mean the motor is
193    // spinning 10x faster than the output
194    var motorVelocity = m_x.get(1, 0) * m_gearing;
195    return m_gearbox.getCurrent(motorVelocity, m_u.get(0, 0)) * Math.signum(m_u.get(0, 0));
196  }
197
198  /**
199   * Sets the input voltage for the arm.
200   *
201   * @param volts The input voltage.
202   */
203  public void setInputVoltage(double volts) {
204    setInput(volts);
205    clampInput(RobotController.getBatteryVoltage());
206  }
207
208  /**
209   * Calculates a rough estimate of the moment of inertia of an arm given its length and mass.
210   *
211   * @param lengthMeters The length of the arm.
212   * @param massKg The mass of the arm.
213   * @return The calculated moment of inertia.
214   */
215  public static double estimateMOI(double lengthMeters, double massKg) {
216    return 1.0 / 3.0 * massKg * lengthMeters * lengthMeters;
217  }
218
219  /**
220   * Updates the state of the arm.
221   *
222   * @param currentXhat The current state estimate.
223   * @param u The system inputs (voltage).
224   * @param dtSeconds The time difference between controller updates.
225   */
226  @Override
227  protected Matrix<N2, N1> updateX(Matrix<N2, N1> currentXhat, Matrix<N1, N1> u, double dtSeconds) {
228    // The torque on the arm is given by τ = F⋅r, where F is the force applied by
229    // gravity and r the distance from pivot to center of mass. Recall from
230    // dynamics that the sum of torques for a rigid body is τ = J⋅α, were τ is
231    // torque on the arm, J is the mass-moment of inertia about the pivot axis,
232    // and α is the angular acceleration in rad/s². Rearranging yields: α = F⋅r/J
233    //
234    // We substitute in F = m⋅g⋅cos(θ), where θ is the angle from horizontal:
235    //
236    //   α = (m⋅g⋅cos(θ))⋅r/J
237    //
238    // Multiply RHS by cos(θ) to account for the arm angle. Further, we know the
239    // arm mass-moment of inertia J of our arm is given by J=1/3 mL², modeled as a
240    // rod rotating about it's end, where L is the overall rod length. The mass
241    // distribution is assumed to be uniform. Substitute r=L/2 to find:
242    //
243    //   α = (m⋅g⋅cos(θ))⋅r/(1/3 mL²)
244    //   α = (m⋅g⋅cos(θ))⋅(L/2)/(1/3 mL²)
245    //   α = 3/2⋅g⋅cos(θ)/L
246    //
247    // This acceleration is next added to the linear system dynamics ẋ=Ax+Bu
248    //
249    //   f(x, u) = Ax + Bu + [0  α]ᵀ
250    //   f(x, u) = Ax + Bu + [0  3/2⋅g⋅cos(θ)/L]ᵀ
251
252    Matrix<N2, N1> updatedXhat =
253        NumericalIntegration.rkdp(
254            (Matrix<N2, N1> x, Matrix<N1, N1> _u) -> {
255              Matrix<N2, N1> xdot = m_plant.getA().times(x).plus(m_plant.getB().times(_u));
256              if (m_simulateGravity) {
257                double alphaGrav = 3.0 / 2.0 * -9.8 * Math.cos(x.get(0, 0)) / m_armLenMeters;
258                xdot = xdot.plus(VecBuilder.fill(0, alphaGrav));
259              }
260              return xdot;
261            },
262            currentXhat,
263            u,
264            dtSeconds);
265
266    // We check for collision after updating xhat
267    if (wouldHitLowerLimit(updatedXhat.get(0, 0))) {
268      return VecBuilder.fill(m_minAngle, 0);
269    }
270    if (wouldHitUpperLimit(updatedXhat.get(0, 0))) {
271      return VecBuilder.fill(m_maxAngle, 0);
272    }
273    return updatedXhat;
274  }
275}