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