Class SimSwerveDrivetrain

java.lang.Object
com.ctre.phoenix6.swerve.SimSwerveDrivetrain

public class SimSwerveDrivetrain extends Object
Simplified swerve drive simulation class.

This class assumes that the swerve drive is perfect, meaning that there is no scrub and the wheels do not slip.

In addition, it assumes the inertia of the robot is governed only by the inertia of the steer module and the individual drive wheels. Robot-wide inertia is not accounted for, and neither is translational vs rotational inertia of the robot.

These assumptions provide a simplified example that can demonstrate the behavior of a swerve drive in simulation. Users are encouraged to expand this model for their own use.

  • Field Details

  • Constructor Details

  • Method Details

    • update

      public void update(double dtSeconds, double supplyVoltage, SwerveModule... modulesToApply)
      Update this simulation for the time duration.

      This performs a simulation update on all the simulated devices

      Parameters:
      dtSeconds - The time delta between this update and the previous update
      supplyVoltage - The voltage as seen at the motor controllers
      modulesToApply - What modules to apply the update to
    • addFriction

      protected double addFriction(double motorVoltage, double frictionVoltage)
      Applies the effects of friction to dampen the motor voltage.
      Parameters:
      motorVoltage - Voltage output by the motor
      frictionVoltage - Voltage required to overcome friction
      Returns:
      Friction-dampened motor voltage