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