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   * Create a SimDrivetrain.
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   * Create a SimDrivetrain .
095   *
096   * @param drivetrainPlant The {@link LinearSystem} representing the robot's drivetrain. This
097   *     system can be 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> drivetrainPlant,
116      DCMotor driveMotor,
117      double gearing,
118      double trackWidthMeters,
119      double wheelRadiusMeters,
120      Matrix<N7, N1> measurementStdDevs) {
121    this.m_plant = drivetrainPlant;
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    // Update state estimate with RK4
152    m_x = NumericalIntegration.rk4(this::getDynamics, m_x, m_u, dtSeconds);
153    m_y = m_x;
154    if (m_measurementStdDevs != null) {
155      m_y = m_y.plus(StateSpaceUtil.makeWhiteNoiseVector(m_measurementStdDevs));
156    }
157  }
158
159  /** Returns the full simulated state of the drivetrain. */
160  Matrix<N7, N1> getState() {
161    return m_x;
162  }
163
164  /**
165   * Get one of the drivetrain states.
166   *
167   * @param state the state to get
168   * @return the state
169   */
170  double getState(State state) {
171    return m_x.get(state.value, 0);
172  }
173
174  private double getOutput(State output) {
175    return m_y.get(output.value, 0);
176  }
177
178  /**
179   * Returns the direction the robot is pointing.
180   *
181   * <p>Note that this angle is counterclockwise-positive, while most gyros are clockwise positive.
182   *
183   * @return The direction the robot is pointing.
184   */
185  public Rotation2d getHeading() {
186    return new Rotation2d(getOutput(State.kHeading));
187  }
188
189  /**
190   * Returns the current pose.
191   *
192   * @return The current pose.
193   */
194  public Pose2d getPose() {
195    return new Pose2d(getOutput(State.kX), getOutput(State.kY), getHeading());
196  }
197
198  /**
199   * Get the right encoder position in meters.
200   *
201   * @return The encoder position.
202   */
203  public double getRightPositionMeters() {
204    return getOutput(State.kRightPosition);
205  }
206
207  /**
208   * Get the right encoder velocity in meters per second.
209   *
210   * @return The encoder velocity.
211   */
212  public double getRightVelocityMetersPerSecond() {
213    return getOutput(State.kRightVelocity);
214  }
215
216  /**
217   * Get the left encoder position in meters.
218   *
219   * @return The encoder position.
220   */
221  public double getLeftPositionMeters() {
222    return getOutput(State.kLeftPosition);
223  }
224
225  /**
226   * Get the left encoder velocity in meters per second.
227   *
228   * @return The encoder velocity.
229   */
230  public double getLeftVelocityMetersPerSecond() {
231    return getOutput(State.kLeftVelocity);
232  }
233
234  /**
235   * Get the current draw of the left side of the drivetrain.
236   *
237   * @return the drivetrain's left side current draw, in amps
238   */
239  public double getLeftCurrentDrawAmps() {
240    var loadIleft =
241        m_motor.getCurrent(
242                getState(State.kLeftVelocity) * m_currentGearing / m_wheelRadiusMeters,
243                m_u.get(0, 0))
244            * Math.signum(m_u.get(0, 0));
245    return loadIleft;
246  }
247
248  /**
249   * Get the current draw of the right side of the drivetrain.
250   *
251   * @return the drivetrain's right side current draw, in amps
252   */
253  public double getRightCurrentDrawAmps() {
254    var loadIright =
255        m_motor.getCurrent(
256                getState(State.kRightVelocity) * m_currentGearing / m_wheelRadiusMeters,
257                m_u.get(1, 0))
258            * Math.signum(m_u.get(1, 0));
259
260    return loadIright;
261  }
262
263  /**
264   * Get the current draw of the drivetrain.
265   *
266   * @return the current draw, in amps
267   */
268  public double getCurrentDrawAmps() {
269    return getLeftCurrentDrawAmps() + getRightCurrentDrawAmps();
270  }
271
272  /**
273   * Get the drivetrain gearing.
274   *
275   * @return the gearing ration
276   */
277  public double getCurrentGearing() {
278    return m_currentGearing;
279  }
280
281  /**
282   * Sets the gearing reduction on the drivetrain. This is commonly used for shifting drivetrains.
283   *
284   * @param newGearRatio The new gear ratio, as output over input.
285   */
286  public void setCurrentGearing(double newGearRatio) {
287    this.m_currentGearing = newGearRatio;
288  }
289
290  /**
291   * Sets the system state.
292   *
293   * @param state The state.
294   */
295  public void setState(Matrix<N7, N1> state) {
296    m_x = state;
297  }
298
299  /**
300   * Sets the system pose.
301   *
302   * @param pose The pose.
303   */
304  public void setPose(Pose2d pose) {
305    m_x.set(State.kX.value, 0, pose.getX());
306    m_x.set(State.kY.value, 0, pose.getY());
307    m_x.set(State.kHeading.value, 0, pose.getRotation().getRadians());
308    m_x.set(State.kLeftPosition.value, 0, 0);
309    m_x.set(State.kRightPosition.value, 0, 0);
310  }
311
312  protected Matrix<N7, N1> getDynamics(Matrix<N7, N1> x, Matrix<N2, N1> u) {
313    // Because G can be factored out of B, we can divide by the old ratio and multiply
314    // by the new ratio to get a new drivetrain model.
315    var B = new Matrix<>(Nat.N4(), Nat.N2());
316    B.assignBlock(0, 0, m_plant.getB().times(this.m_currentGearing / this.m_originalGearing));
317
318    // Because G² can be factored out of A, we can divide by the old ratio squared and multiply
319    // by the new ratio squared to get a new drivetrain model.
320    var A = new Matrix<>(Nat.N4(), Nat.N4());
321    A.assignBlock(
322        0,
323        0,
324        m_plant
325            .getA()
326            .times(
327                (this.m_currentGearing * this.m_currentGearing)
328                    / (this.m_originalGearing * this.m_originalGearing)));
329
330    A.assignBlock(2, 0, Matrix.eye(Nat.N2()));
331
332    var v = (x.get(State.kLeftVelocity.value, 0) + x.get(State.kRightVelocity.value, 0)) / 2.0;
333
334    var xdot = new Matrix<>(Nat.N7(), Nat.N1());
335    xdot.set(0, 0, v * Math.cos(x.get(State.kHeading.value, 0)));
336    xdot.set(1, 0, v * Math.sin(x.get(State.kHeading.value, 0)));
337    xdot.set(
338        2,
339        0,
340        (x.get(State.kRightVelocity.value, 0) - x.get(State.kLeftVelocity.value, 0))
341            / (2.0 * m_rb));
342    xdot.assignBlock(3, 0, A.times(x.block(Nat.N4(), Nat.N1(), 3, 0)).plus(B.times(u)));
343
344    return xdot;
345  }
346
347  /**
348   * Clamp the input vector such that no element exceeds the battery voltage. If any does, the
349   * relative magnitudes of the input will be maintained.
350   *
351   * @param u The input vector.
352   * @return The normalized input.
353   */
354  protected Matrix<N2, N1> clampInput(Matrix<N2, N1> u) {
355    return StateSpaceUtil.desaturateInputVector(u, RobotController.getBatteryVoltage());
356  }
357
358  /** Represents the different states of the drivetrain. */
359  enum State {
360    kX(0),
361    kY(1),
362    kHeading(2),
363    kLeftVelocity(3),
364    kRightVelocity(4),
365    kLeftPosition(5),
366    kRightPosition(6);
367
368    public final int value;
369
370    State(int i) {
371      this.value = i;
372    }
373  }
374
375  /**
376   * Represents a gearing option of the Toughbox mini. 12.75:1 -- 14:50 and 14:50 10.71:1 -- 14:50
377   * 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
378   */
379  public enum KitbotGearing {
380    k12p75(12.75),
381    k10p71(10.71),
382    k8p45(8.45),
383    k7p31(7.31),
384    k5p95(5.95);
385
386    public final double value;
387
388    KitbotGearing(double i) {
389      this.value = i;
390    }
391  }
392
393  /** Represents common motor layouts of the kit drivetrain. */
394  public enum KitbotMotor {
395    kSingleCIMPerSide(DCMotor.getCIM(1)),
396    kDualCIMPerSide(DCMotor.getCIM(2)),
397    kSingleMiniCIMPerSide(DCMotor.getMiniCIM(1)),
398    kDualMiniCIMPerSide(DCMotor.getMiniCIM(2)),
399    kSingleFalcon500PerSide(DCMotor.getFalcon500(1)),
400    kDoubleFalcon500PerSide(DCMotor.getFalcon500(2)),
401    kSingleNEOPerSide(DCMotor.getNEO(1)),
402    kDoubleNEOPerSide(DCMotor.getNEO(2));
403
404    public final DCMotor value;
405
406    KitbotMotor(DCMotor i) {
407      this.value = i;
408    }
409  }
410
411  /** Represents common wheel sizes of the kit drivetrain. */
412  public enum KitbotWheelSize {
413    kSixInch(Units.inchesToMeters(6)),
414    kEightInch(Units.inchesToMeters(8)),
415    kTenInch(Units.inchesToMeters(10));
416
417    public final double value;
418
419    KitbotWheelSize(double i) {
420      this.value = i;
421    }
422  }
423
424  /**
425   * Create a sim for the standard FRC kitbot.
426   *
427   * @param motor The motors installed in the bot.
428   * @param gearing The gearing reduction used.
429   * @param wheelSize The wheel size.
430   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
431   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
432   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
433   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
434   *     point.
435   * @return A sim for the standard FRC kitbot.
436   */
437  public static DifferentialDrivetrainSim createKitbotSim(
438      KitbotMotor motor,
439      KitbotGearing gearing,
440      KitbotWheelSize wheelSize,
441      Matrix<N7, N1> measurementStdDevs) {
442    // MOI estimation -- note that I = mr² for point masses
443    var batteryMoi = 12.5 / 2.2 * Math.pow(Units.inchesToMeters(10), 2);
444    var gearboxMoi =
445        (2.8 /* CIM motor */ * 2 / 2.2 + 2.0 /* Toughbox Mini- ish */)
446            * Math.pow(Units.inchesToMeters(26.0 / 2.0), 2);
447
448    return createKitbotSim(motor, gearing, wheelSize, batteryMoi + gearboxMoi, measurementStdDevs);
449  }
450
451  /**
452   * Create a sim for the standard FRC kitbot.
453   *
454   * @param motor The motors installed in the bot.
455   * @param gearing The gearing reduction used.
456   * @param wheelSize The wheel size.
457   * @param jKgMetersSquared The moment of inertia of the drivebase. This can be calculated using
458   *     SysId.
459   * @param measurementStdDevs Standard deviations for measurements, in the form [x, y, heading,
460   *     left velocity, right velocity, left distance, right distance]ᵀ. Can be null if no noise is
461   *     desired. Gyro standard deviations of 0.0001 radians, velocity standard deviations of 0.05
462   *     m/s, and position measurement standard deviations of 0.005 meters are a reasonable starting
463   *     point.
464   * @return A sim for the standard FRC kitbot.
465   */
466  public static DifferentialDrivetrainSim createKitbotSim(
467      KitbotMotor motor,
468      KitbotGearing gearing,
469      KitbotWheelSize wheelSize,
470      double jKgMetersSquared,
471      Matrix<N7, N1> measurementStdDevs) {
472    return new DifferentialDrivetrainSim(
473        motor.value,
474        gearing.value,
475        jKgMetersSquared,
476        Units.lbsToKilograms(60),
477        wheelSize.value / 2.0,
478        Units.inchesToMeters(26),
479        measurementStdDevs);
480  }
481}