Package frc.robot.swerve
Class MapleSimSwerveDrivetrain
java.lang.Object
frc.robot.swerve.MapleSimSwerveDrivetrain
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 ClassesModifier and TypeClassDescriptionprotected static classRepresents the simulation of a singleSwerveModule.static classstatic class -
Field Summary
FieldsModifier and TypeFieldDescriptionfinal org.ironmaple.simulation.drivesims.SwerveDriveSimulation -
Constructor Summary
ConstructorsConstructorDescriptionMapleSimSwerveDrivetrain(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 TypeMethodDescriptionstatic com.ctre.phoenix6.swerve.SwerveModuleConstants<?,?, ?>[] regulateModuleConstantsForSimulation(com.ctre.phoenix6.swerve.SwerveModuleConstants<?, ?, ?>[] moduleConstants) Regulates allSwerveModuleConstantsfor a drivetrain simulation.voidupdate()Update the simulation.
-
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 simulationrobotMassWithBumpers- the total mass of the robot, including bumpersbumperLengthX- 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- theDCMotormodel for the drive motor, typicallyDCMotor.getKrakenX60Foc()steerMotorModel- theDCMotormodel for the steer motor, typicallyDCMotor.getKrakenX60Foc()wheelCOF- the coefficient of friction of the drive wheelsmoduleLocations- the locations of the swerve modules on the robot, in the orderFL, FR, BL, BRpigeon- thePigeon2IMU used in the drivetrainmodules- theSwerveModules, typically obtained viaSwerveDrivetrain.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
SwerveModuleConstantsfor a drivetrain simulation.This method processes an array of
SwerveModuleConstantsto apply necessary adjustments for simulation purposes, ensuring compatibility and avoiding known bugs.- See Also:
-
regulateModuleConstantForSimulation(SwerveModuleConstants)
-