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