Class MapleSimSwerveDrivetrain

java.lang.Object
frc.robot.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.

  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    protected static class 
    Represents the simulation of a single SwerveModule.
    static class 
     
    static class 
     
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    final org.ironmaple.simulation.drivesims.SwerveDriveSimulation
     
  • Constructor Summary

    Constructors
    Constructor
    Description
    MapleSimSwerveDrivetrain(edu.wpi.first.units.measure.Time simPeriod, edu.wpi.first.units.measure.Mass robotMassWithBumpers, edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY, edu.wpi.first.math.system.plant.DCMotor driveMotorModel, edu.wpi.first.math.system.plant.DCMotor steerMotorModel, double wheelCOF, edu.wpi.first.math.geometry.Translation2d[] moduleLocations, com.ctre.phoenix6.hardware.Pigeon2 pigeon, com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[] modules, com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.CANcoderConfiguration>... moduleConstants)
    Constructs a drivetrain simulation using the specified parameters.
  • Method Summary

    Modifier and Type
    Method
    Description
    static com.ctre.phoenix6.swerve.SwerveModuleConstants<?,?,?>[]
    regulateModuleConstantsForSimulation(com.ctre.phoenix6.swerve.SwerveModuleConstants<?,?,?>[] moduleConstants)
    Regulates all SwerveModuleConstants for a drivetrain simulation.
    void
    Update the simulation.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Field Details

    • mapleSimDrive

      public final org.ironmaple.simulation.drivesims.SwerveDriveSimulation mapleSimDrive
  • Constructor Details

    • MapleSimSwerveDrivetrain

      public MapleSimSwerveDrivetrain(edu.wpi.first.units.measure.Time simPeriod, edu.wpi.first.units.measure.Mass robotMassWithBumpers, edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY, edu.wpi.first.math.system.plant.DCMotor driveMotorModel, edu.wpi.first.math.system.plant.DCMotor steerMotorModel, double wheelCOF, edu.wpi.first.math.geometry.Translation2d[] moduleLocations, com.ctre.phoenix6.hardware.Pigeon2 pigeon, com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[] modules, com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.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 com.ctre.phoenix6.swerve.SwerveModuleConstants<?,?,?>[] regulateModuleConstantsForSimulation(com.ctre.phoenix6.swerve.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)