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.Nat;
009import edu.wpi.first.math.StateSpaceUtil;
010import edu.wpi.first.math.VecBuilder;
011import edu.wpi.first.math.geometry.Pose2d;
012import edu.wpi.first.math.geometry.Rotation2d;
013import edu.wpi.first.math.numbers.N1;
014import edu.wpi.first.math.numbers.N2;
015import edu.wpi.first.math.numbers.N7;
016import edu.wpi.first.math.system.LinearSystem;
017import edu.wpi.first.math.system.NumericalIntegration;
018import edu.wpi.first.math.system.plant.DCMotor;
019import edu.wpi.first.math.system.plant.LinearSystemId;
020import edu.wpi.first.math.util.Units;
021import edu.wpi.first.wpilibj.RobotController;
022
023/**
024 * This class simulates the state of the drivetrain. In simulationPeriodic, users should first set
025 * inputs from motors with {@link #setInputs(double, double)}, call {@link #update(double)} to
026 * update the simulation, and set estimated encoder and gyro positions, as well as estimated
027 * odometry pose. Teams can use {@link edu.wpi.first.wpilibj.smartdashboard.Field2d} to visualize
028 * their robot on the Sim GUI's field.
029 *
030 * <p>Our state-space system is:
031 *
032 * <p>x = [[x, y, theta, vel_l, vel_r, dist_l, dist_r]]ᵀ in the field coordinate system (dist_* are
033 * wheel distances.)
034 *
035 * <p>u = [[voltage_l, voltage_r]]ᵀ This is typically the control input of the last timestep from a
036 * LTVDiffDriveController.
037 *
038 * <p>y = x
039 */
040public class DifferentialDrivetrainSim {
041  private final DCMotor m_motor;
042  private final double m_originalGearing;
043  private final Matrix<N7, N1> m_measurementStdDevs;
044  private double m_currentGearing;
045  private final double m_wheelRadiusMeters;
046
047  @SuppressWarnings("MemberName")
048  private Matrix<N2, N1> m_u;
049
050  @SuppressWarnings("MemberName")
051  private Matrix<N7, N1> m_x;
052
053  @SuppressWarnings("MemberName")
054  private Matrix<N7, N1> m_y;
055
056  private final double m_rb;
057  private final LinearSystem<N2, N2, N2> m_plant;
058
059  /**
060   * Create a SimDrivetrain.
061   *
062   * @param driveMotor A {@link DCMotor} representing the left side of the drivetrain.
063   * @param gearing The gearing ratio between motor and wheel, as output over input. This must be
064   *     the same ratio as the ratio used to identify or create the drivetrainPlant.
065   * @param jKgMetersSquared The moment of inertia of the drivetrain about its center.
066   * @param massKg The mass of the drivebase.
067   * @param wheelRadiusMeters The radius of the wheels on the drivetrain.
068   * @param trackWidthMeters The robot's track width, or distance between left and right wheels.
069   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
070   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
071   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
072   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
073   *     point.
074   */
075  @SuppressWarnings("ParameterName")
076  public DifferentialDrivetrainSim(
077      DCMotor driveMotor,
078      double gearing,
079      double jKgMetersSquared,
080      double massKg,
081      double wheelRadiusMeters,
082      double trackWidthMeters,
083      Matrix<N7, N1> measurementStdDevs) {
084    this(
085        LinearSystemId.createDrivetrainVelocitySystem(
086            driveMotor,
087            massKg,
088            wheelRadiusMeters,
089            trackWidthMeters / 2.0,
090            jKgMetersSquared,
091            gearing),
092        driveMotor,
093        gearing,
094        trackWidthMeters,
095        wheelRadiusMeters,
096        measurementStdDevs);
097  }
098
099  /**
100   * Create a SimDrivetrain .
101   *
102   * @param drivetrainPlant The {@link LinearSystem} representing the robot's drivetrain. This
103   *     system can be created with {@link
104   *     edu.wpi.first.math.system.plant.LinearSystemId#createDrivetrainVelocitySystem(DCMotor,
105   *     double, double, double, double, double)} or {@link
106   *     edu.wpi.first.math.system.plant.LinearSystemId#identifyDrivetrainSystem(double, double,
107   *     double, double)}.
108   * @param driveMotor A {@link DCMotor} representing the drivetrain.
109   * @param gearing The gearingRatio ratio of the robot, as output over input. This must be the same
110   *     ratio as the ratio used to identify or create the drivetrainPlant.
111   * @param trackWidthMeters The distance between the two sides of the drivetrian. Can be found with
112   *     SysId.
113   * @param wheelRadiusMeters The radius of the wheels on the drivetrain, in meters.
114   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
115   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
116   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
117   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
118   *     point.
119   */
120  public DifferentialDrivetrainSim(
121      LinearSystem<N2, N2, N2> drivetrainPlant,
122      DCMotor driveMotor,
123      double gearing,
124      double trackWidthMeters,
125      double wheelRadiusMeters,
126      Matrix<N7, N1> measurementStdDevs) {
127    this.m_plant = drivetrainPlant;
128    this.m_rb = trackWidthMeters / 2.0;
129    this.m_motor = driveMotor;
130    this.m_originalGearing = gearing;
131    this.m_measurementStdDevs = measurementStdDevs;
132    m_wheelRadiusMeters = wheelRadiusMeters;
133    m_currentGearing = m_originalGearing;
134
135    m_x = new Matrix<>(Nat.N7(), Nat.N1());
136    m_u = VecBuilder.fill(0, 0);
137    m_y = new Matrix<>(Nat.N7(), Nat.N1());
138  }
139
140  /**
141   * Sets the applied voltage to the drivetrain. Note that positive voltage must make that side of
142   * the drivetrain travel forward (+X).
143   *
144   * @param leftVoltageVolts The left voltage.
145   * @param rightVoltageVolts The right voltage.
146   */
147  public void setInputs(double leftVoltageVolts, double rightVoltageVolts) {
148    m_u = clampInput(VecBuilder.fill(leftVoltageVolts, rightVoltageVolts));
149  }
150
151  /**
152   * Update the drivetrain states with the current time difference.
153   *
154   * @param dtSeconds the time difference
155   */
156  @SuppressWarnings("LocalVariableName")
157  public void update(double dtSeconds) {
158    // Update state estimate with RK4
159    m_x = NumericalIntegration.rk4(this::getDynamics, m_x, m_u, dtSeconds);
160    m_y = m_x;
161    if (m_measurementStdDevs != null) {
162      m_y = m_y.plus(StateSpaceUtil.makeWhiteNoiseVector(m_measurementStdDevs));
163    }
164  }
165
166  /** Returns the full simulated state of the drivetrain. */
167  Matrix<N7, N1> getState() {
168    return m_x;
169  }
170
171  /**
172   * Get one of the drivetrain states.
173   *
174   * @param state the state to get
175   * @return the state
176   */
177  double getState(State state) {
178    return m_x.get(state.value, 0);
179  }
180
181  private double getOutput(State output) {
182    return m_y.get(output.value, 0);
183  }
184
185  /**
186   * Returns the direction the robot is pointing.
187   *
188   * <p>Note that this angle is counterclockwise-positive, while most gyros are clockwise positive.
189   *
190   * @return The direction the robot is pointing.
191   */
192  public Rotation2d getHeading() {
193    return new Rotation2d(getOutput(State.kHeading));
194  }
195
196  /**
197   * Returns the current pose.
198   *
199   * @return The current pose.
200   */
201  public Pose2d getPose() {
202    return new Pose2d(getOutput(State.kX), getOutput(State.kY), getHeading());
203  }
204
205  /**
206   * Get the right encoder position in meters.
207   *
208   * @return The encoder position.
209   */
210  public double getRightPositionMeters() {
211    return getOutput(State.kRightPosition);
212  }
213
214  /**
215   * Get the right encoder velocity in meters per second.
216   *
217   * @return The encoder velocity.
218   */
219  public double getRightVelocityMetersPerSecond() {
220    return getOutput(State.kRightVelocity);
221  }
222
223  /**
224   * Get the left encoder position in meters.
225   *
226   * @return The encoder position.
227   */
228  public double getLeftPositionMeters() {
229    return getOutput(State.kLeftPosition);
230  }
231
232  /**
233   * Get the left encoder velocity in meters per second.
234   *
235   * @return The encoder velocity.
236   */
237  public double getLeftVelocityMetersPerSecond() {
238    return getOutput(State.kLeftVelocity);
239  }
240
241  /**
242   * Get the current draw of the left side of the drivetrain.
243   *
244   * @return the drivetrain's left side current draw, in amps
245   */
246  public double getLeftCurrentDrawAmps() {
247    var loadIleft =
248        m_motor.getCurrent(
249                getState(State.kLeftVelocity) * m_currentGearing / m_wheelRadiusMeters,
250                m_u.get(0, 0))
251            * Math.signum(m_u.get(0, 0));
252    return loadIleft;
253  }
254
255  /**
256   * Get the current draw of the right side of the drivetrain.
257   *
258   * @return the drivetrain's right side current draw, in amps
259   */
260  public double getRightCurrentDrawAmps() {
261    var loadIright =
262        m_motor.getCurrent(
263                getState(State.kRightVelocity) * m_currentGearing / m_wheelRadiusMeters,
264                m_u.get(1, 0))
265            * Math.signum(m_u.get(1, 0));
266
267    return loadIright;
268  }
269
270  /**
271   * Get the current draw of the drivetrain.
272   *
273   * @return the current draw, in amps
274   */
275  public double getCurrentDrawAmps() {
276    return getLeftCurrentDrawAmps() + getRightCurrentDrawAmps();
277  }
278
279  /**
280   * Get the drivetrain gearing.
281   *
282   * @return the gearing ration
283   */
284  public double getCurrentGearing() {
285    return m_currentGearing;
286  }
287
288  /**
289   * Sets the gearing reduction on the drivetrain. This is commonly used for shifting drivetrains.
290   *
291   * @param newGearRatio The new gear ratio, as output over input.
292   */
293  public void setCurrentGearing(double newGearRatio) {
294    this.m_currentGearing = newGearRatio;
295  }
296
297  /**
298   * Sets the system state.
299   *
300   * @param state The state.
301   */
302  public void setState(Matrix<N7, N1> state) {
303    m_x = state;
304  }
305
306  /**
307   * Sets the system pose.
308   *
309   * @param pose The pose.
310   */
311  public void setPose(Pose2d pose) {
312    m_x.set(State.kX.value, 0, pose.getX());
313    m_x.set(State.kY.value, 0, pose.getY());
314    m_x.set(State.kHeading.value, 0, pose.getRotation().getRadians());
315    m_x.set(State.kLeftPosition.value, 0, 0);
316    m_x.set(State.kRightPosition.value, 0, 0);
317  }
318
319  @SuppressWarnings({"DuplicatedCode", "LocalVariableName", "ParameterName"})
320  protected Matrix<N7, N1> getDynamics(Matrix<N7, N1> x, Matrix<N2, N1> u) {
321    // Because G can be factored out of B, we can divide by the old ratio and multiply
322    // by the new ratio to get a new drivetrain model.
323    var B = new Matrix<>(Nat.N4(), Nat.N2());
324    B.assignBlock(0, 0, m_plant.getB().times(this.m_currentGearing / this.m_originalGearing));
325
326    // Because G^2 can be factored out of A, we can divide by the old ratio squared and multiply
327    // by the new ratio squared to get a new drivetrain model.
328    var A = new Matrix<>(Nat.N4(), Nat.N4());
329    A.assignBlock(
330        0,
331        0,
332        m_plant
333            .getA()
334            .times(
335                (this.m_currentGearing * this.m_currentGearing)
336                    / (this.m_originalGearing * this.m_originalGearing)));
337
338    A.assignBlock(2, 0, Matrix.eye(Nat.N2()));
339
340    var v = (x.get(State.kLeftVelocity.value, 0) + x.get(State.kRightVelocity.value, 0)) / 2.0;
341
342    var xdot = new Matrix<>(Nat.N7(), Nat.N1());
343    xdot.set(0, 0, v * Math.cos(x.get(State.kHeading.value, 0)));
344    xdot.set(1, 0, v * Math.sin(x.get(State.kHeading.value, 0)));
345    xdot.set(
346        2,
347        0,
348        (x.get(State.kRightVelocity.value, 0) - x.get(State.kLeftVelocity.value, 0))
349            / (2.0 * m_rb));
350    xdot.assignBlock(3, 0, A.times(x.block(Nat.N4(), Nat.N1(), 3, 0)).plus(B.times(u)));
351
352    return xdot;
353  }
354
355  /**
356   * Clamp the input vector such that no element exceeds the battery voltage. If any does, the
357   * relative magnitudes of the input will be maintained.
358   *
359   * @param u The input vector.
360   * @return The normalized input.
361   */
362  protected Matrix<N2, N1> clampInput(Matrix<N2, N1> u) {
363    return StateSpaceUtil.desaturateInputVector(u, RobotController.getBatteryVoltage());
364  }
365
366  /** Represents the different states of the drivetrain. */
367  enum State {
368    kX(0),
369    kY(1),
370    kHeading(2),
371    kLeftVelocity(3),
372    kRightVelocity(4),
373    kLeftPosition(5),
374    kRightPosition(6);
375
376    @SuppressWarnings("MemberName")
377    public final int value;
378
379    @SuppressWarnings("ParameterName")
380    State(int i) {
381      this.value = i;
382    }
383  }
384
385  /**
386   * Represents a gearing option of the Toughbox mini. 12.75:1 -- 14:50 and 14:50 10.71:1 -- 14:50
387   * and 16:48 8.45:1 -- 14:50 and 19:45 7.31:1 -- 14:50 and 21:43 5.95:1 -- 14:50 and 24:40
388   */
389  public enum KitbotGearing {
390    k12p75(12.75),
391    k10p71(10.71),
392    k8p45(8.45),
393    k7p31(7.31),
394    k5p95(5.95);
395
396    @SuppressWarnings("MemberName")
397    public final double value;
398
399    @SuppressWarnings("ParameterName")
400    KitbotGearing(double i) {
401      this.value = i;
402    }
403  }
404
405  /** Represents common motor layouts of the kit drivetrain. */
406  public enum KitbotMotor {
407    kSingleCIMPerSide(DCMotor.getCIM(1)),
408    kDualCIMPerSide(DCMotor.getCIM(2)),
409    kSingleMiniCIMPerSide(DCMotor.getMiniCIM(1)),
410    kDualMiniCIMPerSide(DCMotor.getMiniCIM(2)),
411    kSingleFalcon500PerSide(DCMotor.getFalcon500(1)),
412    kDoubleFalcon500PerSide(DCMotor.getFalcon500(2)),
413    kSingleNEOPerSide(DCMotor.getNEO(1)),
414    kDoubleNEOPerSide(DCMotor.getNEO(2));
415
416    @SuppressWarnings("MemberName")
417    public final DCMotor value;
418
419    @SuppressWarnings("ParameterName")
420    KitbotMotor(DCMotor i) {
421      this.value = i;
422    }
423  }
424
425  /** Represents common wheel sizes of the kit drivetrain. */
426  public enum KitbotWheelSize {
427    kSixInch(Units.inchesToMeters(6)),
428    kEightInch(Units.inchesToMeters(8)),
429    kTenInch(Units.inchesToMeters(10)),
430
431    @Deprecated
432    SixInch(Units.inchesToMeters(6)),
433    @Deprecated
434    EightInch(Units.inchesToMeters(8)),
435    @Deprecated
436    TenInch(Units.inchesToMeters(10));
437
438    @SuppressWarnings("MemberName")
439    public final double value;
440
441    @SuppressWarnings("ParameterName")
442    KitbotWheelSize(double i) {
443      this.value = i;
444    }
445  }
446
447  /**
448   * Create a sim for the standard FRC kitbot.
449   *
450   * @param motor The motors installed in the bot.
451   * @param gearing The gearing reduction used.
452   * @param wheelSize The wheel size.
453   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
454   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
455   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
456   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
457   *     point.
458   * @return A sim for the standard FRC kitbot.
459   */
460  public static DifferentialDrivetrainSim createKitbotSim(
461      KitbotMotor motor,
462      KitbotGearing gearing,
463      KitbotWheelSize wheelSize,
464      Matrix<N7, N1> measurementStdDevs) {
465    // MOI estimation -- note that I = m r^2 for point masses
466    var batteryMoi = 12.5 / 2.2 * Math.pow(Units.inchesToMeters(10), 2);
467    var gearboxMoi =
468        (2.8 /* CIM motor */ * 2 / 2.2 + 2.0 /* Toughbox Mini- ish */)
469            * Math.pow(Units.inchesToMeters(26.0 / 2.0), 2);
470
471    return createKitbotSim(motor, gearing, wheelSize, batteryMoi + gearboxMoi, measurementStdDevs);
472  }
473
474  /**
475   * Create a sim for the standard FRC kitbot.
476   *
477   * @param motor The motors installed in the bot.
478   * @param gearing The gearing reduction used.
479   * @param wheelSize The wheel size.
480   * @param jKgMetersSquared The moment of inertia of the drivebase. This can be calculated using
481   *     SysId.
482   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
483   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
484   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
485   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
486   *     point.
487   * @return A sim for the standard FRC kitbot.
488   */
489  @SuppressWarnings("ParameterName")
490  public static DifferentialDrivetrainSim createKitbotSim(
491      KitbotMotor motor,
492      KitbotGearing gearing,
493      KitbotWheelSize wheelSize,
494      double jKgMetersSquared,
495      Matrix<N7, N1> measurementStdDevs) {
496    return new DifferentialDrivetrainSim(
497        motor.value,
498        gearing.value,
499        jKgMetersSquared,
500        Units.lbsToKilograms(60),
501        wheelSize.value / 2.0,
502        Units.inchesToMeters(26),
503        measurementStdDevs);
504  }
505}