Class SwerveDriveConfiguration

java.lang.Object
swervelib.parser.SwerveDriveConfiguration

public class SwerveDriveConfiguration extends Object
Swerve drive configurations used during SwerveDrive construction.
  • Field Details

    • moduleLocationsMeters

      public edu.wpi.first.math.geometry.Translation2d[] moduleLocationsMeters
      Swerve Module locations.
    • imu

      public SwerveIMU imu
      Swerve IMU
    • moduleCount

      public int moduleCount
      Number of modules on the robot.
    • modules

      public SwerveModule[] modules
      Swerve Modules.
    • physicalCharacteristics

      public SwerveModulePhysicalCharacteristics physicalCharacteristics
      Physical characteristics of the swerve drive from physicalproperties.json.
  • Constructor Details

    • SwerveDriveConfiguration

      public SwerveDriveConfiguration(SwerveModuleConfiguration[] moduleConfigs, SwerveIMU swerveIMU, boolean invertedIMU, edu.wpi.first.math.controller.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 the SwerveModule.
      physicalCharacteristics - SwerveModulePhysicalCharacteristics to store in association with self.
  • Method Details

    • createModules

      public SwerveModule[] createModules(SwerveModuleConfiguration[] swerves, edu.wpi.first.math.controller.SimpleMotorFeedforward driveFeedforward)
      Create modules based off of the SwerveModuleConfiguration.
      Parameters:
      swerves - Swerve constants.
      driveFeedforward - Drive feedforward created using SwerveMath.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.