Package swervelib.parser
Class SwerveDriveConfiguration
java.lang.Object
swervelib.parser.SwerveDriveConfiguration
Swerve drive configurations used during SwerveDrive construction.
-
Field Summary
Modifier and TypeFieldDescriptionSwerve IMUfinal int
Number of modules on the robot.Swerve Module locations.Swerve Modules.Physical characteristics of the swerve drive from physicalproperties.json. -
Constructor Summary
ConstructorDescriptionSwerveDriveConfiguration
(SwerveModuleConfiguration[] moduleConfigs, SwerveIMU swerveIMU, boolean invertedIMU, SimpleMotorFeedforward driveFeedforward, SwerveModulePhysicalCharacteristics physicalCharacteristics) Create swerve drive configuration. -
Method Summary
Modifier and TypeMethodDescriptioncreateModules
(SwerveModuleConfiguration[] swerves, SimpleMotorFeedforward driveFeedforward) Create modules based off of the SwerveModuleConfiguration.double
Calculate the Drive Base Radius
-
Field Details
-
moduleCount
public final int moduleCountNumber of modules on the robot. -
moduleLocationsMeters
Swerve Module locations. -
imu
Swerve IMU -
modules
Swerve Modules. -
physicalCharacteristics
Physical characteristics of the swerve drive from physicalproperties.json.
-
-
Constructor Details
-
SwerveDriveConfiguration
public SwerveDriveConfiguration(SwerveModuleConfiguration[] moduleConfigs, SwerveIMU swerveIMU, boolean invertedIMU, SimpleMotorFeedforward driveFeedforward, SwerveModulePhysicalCharacteristics physicalCharacteristics) Create swerve drive configuration.- Parameters:
moduleConfigs
- Module configuration.swerveIMU
- Swerve IMU.invertedIMU
- Invert the IMU.driveFeedforward
- The drive motor feedforward to use for theSwerveModule
.physicalCharacteristics
-SwerveModulePhysicalCharacteristics
to store in association with self.
-
-
Method Details
-
createModules
public SwerveModule[] createModules(SwerveModuleConfiguration[] swerves, SimpleMotorFeedforward driveFeedforward) Create modules based off of the SwerveModuleConfiguration.- Parameters:
swerves
- Swerve constants.driveFeedforward
- Drive feedforward created usingSwerveMath.createDriveFeedforward(double, double, double)
.- Returns:
- Swerve Modules.
-
getDriveBaseRadiusMeters
public double getDriveBaseRadiusMeters()Calculate the Drive Base Radius- Returns:
- Drive base radius from center of robot to the farthest wheel in meters.
-