Package frc.robot.simulation
Class MapleSimSwerveDrivetrain
java.lang.Object
frc.robot.simulation.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.-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionprotected static class
Represents the simulation of a singleSwerveModule
.static class
static class
-
Constructor Summary
ConstructorsConstructorDescriptionConstructs a MapleSimSwerveDrivetrain with specified config. -
Method Summary
Modifier and TypeMethodDescriptionorg.ironmaple.simulation.drivesims.SwerveDriveSimulation
Gets the SwerveModuleSimulation injected into the SwerveDrivetrain.static com.ctre.phoenix6.swerve.SwerveModuleConstants<?,
?, ?>[] regulateModuleConstantsForSimulation
(com.ctre.phoenix6.swerve.SwerveModuleConstants<?, ?, ?>[] moduleConstants) Regulates allSwerveModuleConstants
for a drivetrain simulation.void
Resets simulation pose.void
update()
Update the simulation.
-
Constructor Details
-
MapleSimSwerveDrivetrain
Constructs a MapleSimSwerveDrivetrain with specified config.- Parameters:
config
- the config to apply
-
-
Method Details
-
getDriveSimulation
public org.ironmaple.simulation.drivesims.SwerveDriveSimulation getDriveSimulation()Gets the SwerveModuleSimulation injected into the SwerveDrivetrain.- Returns:
- the swerveModuleSimulation of this drivetrain
-
resetSimulationPose
public void resetSimulationPose()Resets simulation pose. -
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 allSwerveModuleConstants
for a drivetrain simulation. This method processes an array ofSwerveModuleConstants
to apply necessary adjustments for simulation purposes, ensuring compatibility and avoiding known bugs.- Parameters:
moduleConstants
- unregulated moduleConstants for each swerve module- Returns:
- regulated swerve module constants as per sim requirements
- See Also:
-
regulateModuleConstantForSimulation(SwerveModuleConstants)
-