Class SimSwerveDrivetrainConfig

java.lang.Object
frc.robot.simulation.SimSwerveDrivetrainConfig

public class SimSwerveDrivetrainConfig extends Object
Configuration helper for the MapleSimSwerveDrivetrain class.
  • Constructor Summary

    Constructors
    Constructor
    Description
     
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.units.measure.Distance
    Get the length of the robot with the bumper.
    edu.wpi.first.units.measure.Distance
    Get the width of the robot with bumper.
    Get the default configuration of a MapleSimSwerveDrivetrain.
    com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.CANcoderConfiguration>[]
    Gets the module constants of all of the modules in the drivetrain.
    edu.wpi.first.math.system.plant.DCMotor
    Get the drive motor used in the module.
    edu.wpi.first.math.geometry.Translation2d[]
    Get the locations of the modules.
    com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[]
    Get the swerve modules in the drivetrain.
    edu.wpi.first.math.system.plant.DCMotor
    Get the steer motor used in the module.
    com.ctre.phoenix6.hardware.Pigeon2
    Get the pigeon IMU used in the drivetrain.
    edu.wpi.first.units.measure.Mass
    Get the robot mass with bumpers.
    edu.wpi.first.math.geometry.Pose2d
    Get the starting pose of the drivetrain.
    double
    Get the Coefficient of Friction of the module wheel.
    withBumperLength(edu.wpi.first.units.measure.Distance bumperLength)
    Apply the length of the robot with the bumper on.
    withBumperWidth(edu.wpi.first.units.measure.Distance bumperWidth)
    Apply the length of the robot with the bumper on.
    withModuleConstants(com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.CANcoderConfiguration>... moduleConsts)
    Applies the module constants for each of the modules in the drivetrain.
    withModuleDriveMotor(edu.wpi.first.math.system.plant.DCMotor modulesDriveMotor)
    Applies the drive motor used for each of the modules in the drivetrain.
    withModuleLocations(edu.wpi.first.math.geometry.Translation2d[] moduleLocs)
    Applies the module locations of the drivetrain.
    withModules(com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[] swerveModules)
    Applies all the modules to this drivetrain config.
    withModuleSteerMotor(edu.wpi.first.math.system.plant.DCMotor modulesSteerMotor)
    Applies the steer motor used for each of the modules in the drivetrain.
    withPigeon(com.ctre.phoenix6.hardware.Pigeon2 pigeonIMU)
    Applies the pigeon IMU that is being used in this drivetrain.
    withRobotMass(edu.wpi.first.units.measure.Mass robotMassWithBumper)
    Apply the mass of the robot with bumpers.
    withStartingPose(edu.wpi.first.math.geometry.Pose2d startPose)
    Apply a starting pose where the drivetrain will start at.
    withWheelCOF(double wheelCoefficientOfFriction)
    Applies the Coefficient of Friction of the wheel material used on the modules.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • SimSwerveDrivetrainConfig

      public SimSwerveDrivetrainConfig()
  • Method Details

    • getDefault

      public static SimSwerveDrivetrainConfig getDefault()
      Get the default configuration of a MapleSimSwerveDrivetrain.
      Returns:
      the default configuration
    • withStartingPose

      public SimSwerveDrivetrainConfig withStartingPose(edu.wpi.first.math.geometry.Pose2d startPose)
      Apply a starting pose where the drivetrain will start at.
      Parameters:
      startPose - the starting pose
      Returns:
      this config
    • withRobotMass

      public SimSwerveDrivetrainConfig withRobotMass(edu.wpi.first.units.measure.Mass robotMassWithBumper)
      Apply the mass of the robot with bumpers.
      Parameters:
      robotMassWithBumper - robot mass with bumpers
      Returns:
      this config
    • withBumperLength

      public SimSwerveDrivetrainConfig withBumperLength(edu.wpi.first.units.measure.Distance bumperLength)
      Apply the length of the robot with the bumper on.
      Parameters:
      bumperLength - length of the robot with bumper
      Returns:
      this config
    • withBumperWidth

      public SimSwerveDrivetrainConfig withBumperWidth(edu.wpi.first.units.measure.Distance bumperWidth)
      Apply the length of the robot with the bumper on.
      Parameters:
      bumperWidth - width of the robot with bumper
      Returns:
      this config
    • withModuleDriveMotor

      public SimSwerveDrivetrainConfig withModuleDriveMotor(edu.wpi.first.math.system.plant.DCMotor modulesDriveMotor)
      Applies the drive motor used for each of the modules in the drivetrain.
      Parameters:
      modulesDriveMotor - the drive motor used in the module
      Returns:
      this config
    • withModuleSteerMotor

      public SimSwerveDrivetrainConfig withModuleSteerMotor(edu.wpi.first.math.system.plant.DCMotor modulesSteerMotor)
      Applies the steer motor used for each of the modules in the drivetrain.
      Parameters:
      modulesSteerMotor - the steer motor used in the module
      Returns:
      this config
    • withWheelCOF

      public SimSwerveDrivetrainConfig withWheelCOF(double wheelCoefficientOfFriction)
      Applies the Coefficient of Friction of the wheel material used on the modules.
      Parameters:
      wheelCoefficientOfFriction - Coefficient of Friction of the wheel
      Returns:
      this config
    • withModuleLocations

      public SimSwerveDrivetrainConfig withModuleLocations(edu.wpi.first.math.geometry.Translation2d[] moduleLocs)
      Applies the module locations of the drivetrain.
      Parameters:
      moduleLocs - the locations of the modules
      Returns:
      this config
    • withPigeon

      public SimSwerveDrivetrainConfig withPigeon(com.ctre.phoenix6.hardware.Pigeon2 pigeonIMU)
      Applies the pigeon IMU that is being used in this drivetrain.
      Parameters:
      pigeonIMU - the pigeon IMU
      Returns:
      this config
    • withModules

      public SimSwerveDrivetrainConfig withModules(com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[] swerveModules)
      Applies all the modules to this drivetrain config.
      Parameters:
      swerveModules - the modules used on this drivetrain
      Returns:
      this config
    • withModuleConstants

      public SimSwerveDrivetrainConfig withModuleConstants(com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.CANcoderConfiguration>... moduleConsts)
      Applies the module constants for each of the modules in the drivetrain.
      Parameters:
      moduleConsts - the module constants
      Returns:
      this config
    • getRobotMass

      public edu.wpi.first.units.measure.Mass getRobotMass()
      Get the robot mass with bumpers.
      Returns:
      the robot mass with bumpers
    • getBumperWidth

      public edu.wpi.first.units.measure.Distance getBumperWidth()
      Get the width of the robot with bumper.
      Returns:
      the with of the robot with the bumper on.
    • getBumperLength

      public edu.wpi.first.units.measure.Distance getBumperLength()
      Get the length of the robot with the bumper.
      Returns:
      the length of the robot with the bumper on.
    • getModuleDriveMotor

      public edu.wpi.first.math.system.plant.DCMotor getModuleDriveMotor()
      Get the drive motor used in the module.
      Returns:
      the drive motor type of the module
    • getModuleSteerMotor

      public edu.wpi.first.math.system.plant.DCMotor getModuleSteerMotor()
      Get the steer motor used in the module.
      Returns:
      the steer motor of the module
    • getWheelCOF

      public double getWheelCOF()
      Get the Coefficient of Friction of the module wheel.
      Returns:
      the COF of the wheel
    • getModuleLocations

      public edu.wpi.first.math.geometry.Translation2d[] getModuleLocations()
      Get the locations of the modules.
      Returns:
      the locations of the modules.
    • getPigeon

      public com.ctre.phoenix6.hardware.Pigeon2 getPigeon()
      Get the pigeon IMU used in the drivetrain.
      Returns:
      the pigeon imu used in the module
    • getModules

      public com.ctre.phoenix6.swerve.SwerveModule<com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.TalonFX,com.ctre.phoenix6.hardware.CANcoder>[] getModules()
      Get the swerve modules in the drivetrain.
      Returns:
      list of all the modules in the drivetrain
    • getModuleConstants

      public com.ctre.phoenix6.swerve.SwerveModuleConstants<com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.TalonFXConfiguration,com.ctre.phoenix6.configs.CANcoderConfiguration>[] getModuleConstants()
      Gets the module constants of all of the modules in the drivetrain.
      Returns:
      the module constants in the drivetrain
    • getStartingPose

      public edu.wpi.first.math.geometry.Pose2d getStartingPose()
      Get the starting pose of the drivetrain.
      Returns:
      starting pose of the simulated drivetrain