Package swervelib.simulation
Class SwerveModuleSimulation
java.lang.Object
swervelib.simulation.SwerveModuleSimulation
Class that wraps around
SwerveModuleSimulation-
Field Summary
FieldsModifier and TypeFieldDescriptionMapleSim module. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoidconfigureSimModule(SwerveModuleSimulation simModule, SwerveModulePhysicalCharacteristics physicalCharacteristics) Configure the maple sim moduleGet the simulated swerve module position.getState()Get theSwerveModuleStateof the simulated module.voidrunAngleMotorCharacterization(double volts) Runs a drive motor characterization on the sim module.voidrunDriveMotorCharacterization(Rotation2d desiredFacing, double volts) Runs a drive motor characterization on the sim module.voidupdateStateAndPosition(SwerveModuleState desiredState) Update the position and state of the module.
-
Field Details
-
mapleSimModule
MapleSim module.
-
-
Constructor Details
-
SwerveModuleSimulation
public SwerveModuleSimulation()
-
-
Method Details
-
configureSimModule
public void configureSimModule(SwerveModuleSimulation simModule, SwerveModulePhysicalCharacteristics physicalCharacteristics) Configure the maple sim module- Parameters:
simModule- theSwerveModuleSimulationobject for simulationphysicalCharacteristics- Physical characteristics of the swerve drive from the JSON or built.
-
updateStateAndPosition
Update the position and state of the module. Called fromSwerveModule.setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState, boolean, boolean)function when simulated.- Parameters:
desiredState- State the swerve module is set to.
-
runDriveMotorCharacterization
Runs a drive motor characterization on the sim module. This is called fromSwerveDriveTest.runDriveMotorsCharacterizationOnSimModules(SwerveDrive, double, boolean)to run sysId during simulation- Parameters:
desiredFacing- the desired facing of the modulevolts- the voltage to run
-
runAngleMotorCharacterization
public void runAngleMotorCharacterization(double volts) Runs a drive motor characterization on the sim module. This method is called fromSwerveDriveTest.runAngleMotorsCharacterizationOnSimModules(SwerveDrive, double)to run sysId during simulation- Parameters:
volts- the voltage to run
-
getPosition
Get the simulated swerve module position.- Returns:
SwerveModulePositionof the simulated module.
-
getState
Get theSwerveModuleStateof the simulated module.- Returns:
SwerveModuleStateof the simulated module.
-