Package swervelib.parser
Class SwerveDriveConfiguration
java.lang.Object
swervelib.parser.SwerveDriveConfiguration
Swerve drive configurations used during SwerveDrive construction.
-
Field Summary
FieldsModifier and TypeFieldDescriptionSwerve IMUfinal intNumber of modules on the robot.Swerve Module locations.Swerve Modules.Physical characteristics of the swerve drive from physicalproperties.json. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveDriveConfiguration(SwerveModuleConfiguration[] moduleConfigs, SwerveIMU swerveIMU, boolean invertedIMU, SwerveModulePhysicalCharacteristics physicalCharacteristics) Create swerve drive configuration. -
Method Summary
Modifier and TypeMethodDescriptioncreateModules(SwerveModuleConfiguration[] swerves) Create modules based off of the SwerveModuleConfiguration.Get theDCMotorcorresponding to the first module configuration.doubleCalculate the Drive Base RadiusGet theDCMotorcorresponding to the first module's configuration.Get the gyro simulation for the robot.doubleGet the tracklength of the swerve modules.doubleGet the trackwidth of the swerve modules.
-
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, SwerveModulePhysicalCharacteristics physicalCharacteristics) Create swerve drive configuration.- Parameters:
moduleConfigs- Module configuration.swerveIMU- Swerve IMU.invertedIMU- Invert the IMU.physicalCharacteristics-SwerveModulePhysicalCharacteristicsto store in association with self.
-
-
Method Details
-
createModules
Create modules based off of the SwerveModuleConfiguration.- Parameters:
swerves- Swerve constants.- 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.
-
getTrackwidth
public double getTrackwidth()Get the trackwidth of the swerve modules.- Returns:
- Effective trackwdtih in Meters
-
getTracklength
public double getTracklength()Get the tracklength of the swerve modules.- Returns:
- Effective tracklength in Meters
-
getDriveMotorSim
Get theDCMotorcorresponding to the first module's configuration.- Returns:
DCMotorof the drive motor.
-
getAngleMotorSim
Get theDCMotorcorresponding to the first module configuration.- Returns:
DCMotorof the angle motor.
-
getGyroSim
Get the gyro simulation for the robot.- Returns:
GyroSimulationgyro simulation.
-