Class DriveTrainSimulationConfig
Stores the configurations for a swerve drive simulation.
This class is used to hold all the parameters necessary for simulating a swerve drivetrain, allowing for realistic performance testing and evaluation.
-
Field Summary
Modifier and TypeFieldDescriptionedu.wpi.first.units.measure.Distance
edu.wpi.first.units.measure.Distance
edu.wpi.first.units.measure.Mass
-
Constructor Summary
ConstructorDescriptionDriveTrainSimulationConfig
(edu.wpi.first.units.measure.Mass robotMass, edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY, edu.wpi.first.units.measure.Distance trackLengthX, edu.wpi.first.units.measure.Distance trackWidthY, Supplier<SwerveModuleSimulation> swerveModuleSimulationFactory, Supplier<GyroSimulation> gyroSimulationFactory) Ordinary Constructor -
Method Summary
Modifier and TypeMethodDescriptionstatic DriveTrainSimulationConfig
Default()
Default Constructor.edu.wpi.first.units.measure.Distance
double
Calculates the density of the robot.edu.wpi.first.units.measure.Distance
Calculates the track length in the X direction.edu.wpi.first.units.measure.Distance
Calculates the track width in the Y direction.withBumperSize
(edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY) Sets the bumper size.withCustomModuleTranslations
(Translation2d[] moduleTranslations) Sets custom module translations.withGyro
(Supplier<GyroSimulation> gyroSimulationFactory) Sets the gyro simulation factory.withRobotMass
(edu.wpi.first.units.measure.Mass robotMass) Sets the robot mass.withSwerveModule
(Supplier<SwerveModuleSimulation> swerveModuleSimulationFactory) Sets the swerve module simulation factory.withTrackLengthTrackWidth
(edu.wpi.first.units.measure.Distance trackLengthX, edu.wpi.first.units.measure.Distance trackWidthY) Sets the track length and width.
-
Field Details
-
robotMass
public edu.wpi.first.units.measure.Mass robotMass -
bumperLengthX
public edu.wpi.first.units.measure.Distance bumperLengthX -
bumperWidthY
public edu.wpi.first.units.measure.Distance bumperWidthY -
swerveModuleSimulationFactory
-
gyroSimulationFactory
-
moduleTranslations
-
-
Constructor Details
-
DriveTrainSimulationConfig
public DriveTrainSimulationConfig(edu.wpi.first.units.measure.Mass robotMass, edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY, edu.wpi.first.units.measure.Distance trackLengthX, edu.wpi.first.units.measure.Distance trackWidthY, Supplier<SwerveModuleSimulation> swerveModuleSimulationFactory, Supplier<GyroSimulation> gyroSimulationFactory) Ordinary Constructor
Creates an instance of
DriveTrainSimulationConfig
with specified parameters.- Parameters:
robotMass
- the mass of the robot, including bumpers.bumperLengthX
- the length of the bumper (distance from front to back).bumperWidthY
- the width of the bumper (distance from left to right).trackLengthX
- the distance between the front and rear wheels.trackWidthY
- the distance between the left and right wheels.swerveModuleSimulationFactory
- the factory that creates appropriate swerve module simulation for the drivetrain.gyroSimulationFactory
- the factory that creates appropriate gyro simulation for the drivetrain.
-
-
Method Details
-
Default
Default Constructor.
Creates a
DriveTrainSimulationConfig
with all the data set to default values.Though the config starts with default values, any configuration can be modified after creation.
The default configurations are:
- Robot Mass of 45 kilograms.
- Bumper Length of 0.76 meters.
- Bumper Width of 0.76 meters.
- Track Length of 0.52 meters.
- Track Width of 0.52 meters.
- Default swerve module simulations based on Falcon 500 motors.
- Default gyro simulation using the Pigeon2 gyro.
- Returns:
- a new instance of
DriveTrainSimulationConfig
with all configs set to default values.
-
withRobotMass
Sets the robot mass.
Updates the mass of the robot in kilograms.
- Parameters:
robotMass
- the new mass of the robot.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
withBumperSize
public DriveTrainSimulationConfig withBumperSize(edu.wpi.first.units.measure.Distance bumperLengthX, edu.wpi.first.units.measure.Distance bumperWidthY) Sets the bumper size.
Updates the dimensions of the bumper.
- Parameters:
bumperLengthX
- the length of the bumper.bumperWidthY
- the width of the bumper.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
withTrackLengthTrackWidth
public DriveTrainSimulationConfig withTrackLengthTrackWidth(edu.wpi.first.units.measure.Distance trackLengthX, edu.wpi.first.units.measure.Distance trackWidthY) Sets the track length and width.
Updates the translations for the swerve modules based on the specified track length and track width.
For non-rectangular chassis configuration, use
withCustomModuleTranslations(Translation2d[])
instead.- Parameters:
trackLengthX
- the distance between the front and rear wheels.trackWidthY
- the distance between the left and right wheels.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
withCustomModuleTranslations
Sets custom module translations.
Updates the translations of the swerve modules with user-defined values.
For ordinary rectangular modules configuration, use
withTrackLengthTrackWidth(Distance, Distance)
instead.- Parameters:
moduleTranslations
- the custom translations for the swerve modules.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
withSwerveModule
public DriveTrainSimulationConfig withSwerveModule(Supplier<SwerveModuleSimulation> swerveModuleSimulationFactory) Sets the swerve module simulation factory.
Updates the factory used to create swerve module simulations.
- Parameters:
swerveModuleSimulationFactory
- the new factory for swerve module simulations.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
withGyro
Sets the gyro simulation factory.
Updates the factory used to create gyro simulations.
- Parameters:
gyroSimulationFactory
- the new factory for gyro simulations.- Returns:
- the current instance of
DriveTrainSimulationConfig
for method chaining.
-
getDensityKgPerSquaredMeters
public double getDensityKgPerSquaredMeters()Calculates the density of the robot.
Returns the density of the robot based on its mass and bumper dimensions.
- Returns:
- the density in kilograms per square meter.
-
trackLengthX
public edu.wpi.first.units.measure.Distance trackLengthX()Calculates the track length in the X direction.
Returns the total distance between the frontmost and rearmost module translations in the X direction.
- Returns:
- the track length.
- Throws:
IllegalStateException
- if the module translations are empty.
-
trackWidthY
public edu.wpi.first.units.measure.Distance trackWidthY()Calculates the track width in the Y direction.
Returns the total distance between the leftmost and rightmost module translations in the Y direction.
- Returns:
- the track width.
- Throws:
IllegalStateException
- if the module translations are empty.
-
driveBaseRadius
public edu.wpi.first.units.measure.Distance driveBaseRadius()
-