Class MapleSimSwerveDrivetrain

java.lang.Object
frc.spectrumLib.swerve.MapleSimSwerveDrivetrain

public class MapleSimSwerveDrivetrain extends Object

Injects Maple-Sim simulation data into a CTRE swerve drivetrain.

This class retrieves simulation data from Maple-Sim and injects it into the CTRE SwerveDrivetrain instance.

It replaces the SimSwerveDrivetrain class.

  • Field Details

  • Constructor Details

    • MapleSimSwerveDrivetrain

      public MapleSimSwerveDrivetrain(Time simPeriod, Mass robotMassWithBumpers, Distance bumperLengthX, Distance bumperWidthY, DCMotor driveMotorModel, DCMotor steerMotorModel, double wheelCOF, Translation2d[] moduleLocations, Pigeon2 pigeon, SwerveModule<TalonFX,TalonFX,CANcoder>[] modules, SwerveModuleConstants<TalonFXConfiguration,TalonFXConfiguration,CANcoderConfiguration>... moduleConstants)

      Constructs a drivetrain simulation using the specified parameters.

      Parameters:
      simPeriod - the time period of the simulation
      robotMassWithBumpers - the total mass of the robot, including bumpers
      bumperLengthX - the length of the bumper along the X-axis (influences the collision space of the robot)
      bumperWidthY - the width of the bumper along the Y-axis (influences the collision space of the robot)
      driveMotorModel - the DCMotor model for the drive motor, typically DCMotor.getKrakenX60Foc()
      steerMotorModel - the DCMotor model for the steer motor, typically DCMotor.getKrakenX60Foc()
      wheelCOF - the coefficient of friction of the drive wheels
      moduleLocations - the locations of the swerve modules on the robot, in the order FL, FR, BL, BR
      pigeon - the Pigeon2 IMU used in the drivetrain
      modules - the SwerveModules, typically obtained via SwerveDrivetrain.getModules()
      moduleConstants - the constants for the swerve modules
  • Method Details

    • update

      public void update()

      Update the simulation.

      Updates the Maple-Sim simulation and injects the results into the simulated CTRE devices, including motors and the IMU.

    • regulateModuleConstantsForSimulation

      public static SwerveModuleConstants<?,?,?>[] regulateModuleConstantsForSimulation(SwerveModuleConstants<?,?,?>[] moduleConstants)

      Regulates all SwerveModuleConstants for a drivetrain simulation.

      This method processes an array of SwerveModuleConstants to apply necessary adjustments for simulation purposes, ensuring compatibility and avoiding known bugs.

      See Also:
      • regulateModuleConstantForSimulation(SwerveModuleConstants)