Class DriveTrain

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frc.robot.Subsystems.DriveTrain.DriveTrain
All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem
Direct Known Subclasses:
DriveTrainRealIO, DriveTrainSimIO

public abstract class DriveTrain extends edu.wpi.first.wpilibj2.command.SubsystemBase
The drive subsystem.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    static final DriveTrain
     
    edu.wpi.first.math.kinematics.SwerveModuleState[]
    The desired module states.
    The drive train's SwerveModule objects.
  • Constructor Summary

    Constructors
    Modifier
    Constructor
    Description
    protected
    Creates a new DriveTrain.
  • Method Summary

    Modifier and Type
    Method
    Description
    edu.wpi.first.math.kinematics.ChassisSpeeds
    discretize_chassis_speeds(edu.wpi.first.math.kinematics.ChassisSpeeds speeds)
    Accounts for drift while simultaneously translating and rotating through discretization.
    abstract edu.wpi.first.math.geometry.Rotation2d
    Gets either the measured yaw from the AHRS or the calculated angle from the simulation.
    abstract double
    Returns the rate at which the gyro is spinning.
    edu.wpi.first.math.kinematics.SwerveModulePosition[]
    Returns the measured swerve module positions for odometry.
    edu.wpi.first.math.kinematics.SwerveModuleState[]
    Returns the measured swerve module states for odometry and telemetry.
    edu.wpi.first.math.kinematics.ChassisSpeeds
    Calculates current speeds using SwerveDriveKinematics odometry.
    edu.wpi.first.math.kinematics.ChassisSpeeds
    Calculates current target speeds using SwerveDriveKinematics odometry and target states.
    protected abstract SwerveModule
    initializeModule(int drive_port, int steer_port, int sensor_port)
    Creates either a SwerveModuleRealIO or SwerveModuleSimIO object.
    void
     
    abstract void
    Resets the gyroscope angle to 0.
    void
    setAccelerationFeedforwards(double[] feedforwards)
     
    void
    setModules(edu.wpi.first.math.kinematics.SwerveModuleState[] module_states)
    Sends calculated inputs to swerve modules.
    void
    setSwerveDrive(double x_speed, double y_speed, double a_speed)
    Calculates and sends inputs to swerve modules given field-relative speeds.
    void
    setSwerveDrive(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds)
    Calculates and sends inputs to swerve modules given robot-relative speeds.
    void
    setSwerveDrive(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds, boolean discretize)
    Calculates and sends inputs to swerve modules given robot-relative speeds.

    Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase

    addChild, getName, getSubsystem, initSendable, setName, setSubsystem

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait

    Methods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem

    defer, getCurrentCommand, getDefaultCommand, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
  • Field Details

    • instance

      public static final DriveTrain instance
    • modules

      public SwerveModule[] modules
      The drive train's SwerveModule objects.
    • module_states

      public edu.wpi.first.math.kinematics.SwerveModuleState[] module_states
      The desired module states.
  • Constructor Details

    • DriveTrain

      protected DriveTrain()
      Creates a new DriveTrain.
  • Method Details

    • setSwerveDrive

      public void setSwerveDrive(double x_speed, double y_speed, double a_speed)
      Calculates and sends inputs to swerve modules given field-relative speeds. Calls setSwerveDrive(ChassisSpeeds).
      Parameters:
      x_speed - The X-axis speed in m/s. Forward is positive.
      y_speed - The Y-axis speed in m/s. Left is positive.
      a_speed - Angular speed in rad/s. CCW is positive.
    • setSwerveDrive

      public void setSwerveDrive(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds)
      Calculates and sends inputs to swerve modules given robot-relative speeds. Assumes discretization is needed.
      Parameters:
      chassis_speeds - The desired robot-relative chassis speeds.
    • setSwerveDrive

      public void setSwerveDrive(edu.wpi.first.math.kinematics.ChassisSpeeds chassis_speeds, boolean discretize)
      Calculates and sends inputs to swerve modules given robot-relative speeds.
      Parameters:
      chassis_speeds - The desired robot-relative chassis speeds.
      discretize - Whether or not to perform discretization. Some library methods provide pre-discretized chassis speeds.
    • setModules

      public void setModules(edu.wpi.first.math.kinematics.SwerveModuleState[] module_states)
      Sends calculated inputs to swerve modules.
      Parameters:
      module_states - The desired module states.
    • discretize_chassis_speeds

      public edu.wpi.first.math.kinematics.ChassisSpeeds discretize_chassis_speeds(edu.wpi.first.math.kinematics.ChassisSpeeds speeds)
      Accounts for drift while simultaneously translating and rotating through discretization.
      Parameters:
      speeds - The desired chassis speeds.
      Returns:
      The adjusted chassis speeds.
    • getModulePositions

      public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions()
      Returns the measured swerve module positions for odometry.
      Returns:
      The measured swerve module positions.
    • getModuleStates

      public edu.wpi.first.math.kinematics.SwerveModuleState[] getModuleStates()
      Returns the measured swerve module states for odometry and telemetry.
      Returns:
      The measured swerve module states.
    • getOdomSpeeds

      public edu.wpi.first.math.kinematics.ChassisSpeeds getOdomSpeeds()
      Calculates current speeds using SwerveDriveKinematics odometry.
      Returns:
      The calculated robot-relative chassis speeds.
    • getTargetOdomSpeeds

      public edu.wpi.first.math.kinematics.ChassisSpeeds getTargetOdomSpeeds()
      Calculates current target speeds using SwerveDriveKinematics odometry and target states.
      Returns:
      The calculated robot-relative chassis speeds.
    • setAccelerationFeedforwards

      public void setAccelerationFeedforwards(double[] feedforwards)
    • getGyroAngle

      public abstract edu.wpi.first.math.geometry.Rotation2d getGyroAngle()
      Gets either the measured yaw from the AHRS or the calculated angle from the simulation. Forward is 0, CCW is positive.
      Returns:
      The robot yaw.
    • getGyroRate

      public abstract double getGyroRate()
      Returns the rate at which the gyro is spinning.
      Returns:
      The gyro rate in degrees per second.
    • resetGyroAngle

      public abstract void resetGyroAngle()
      Resets the gyroscope angle to 0.
    • initializeModule

      protected abstract SwerveModule initializeModule(int drive_port, int steer_port, int sensor_port)
      Creates either a SwerveModuleRealIO or SwerveModuleSimIO object.
      Parameters:
      drive_port - The port number of the drive motor.
      steer_port - The port number of the steer motor.
      sensor_port - The port number of the module's CANcoder.
      Returns:
      The constructed SwerveModule object.
    • periodic

      public void periodic()