Class FrcSwerveDrive

java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
frclib.drivebase.FrcRobotDrive
frclib.drivebase.FrcSwerveDrive
All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable, edu.wpi.first.wpilibj2.command.Subsystem

public class FrcSwerveDrive extends FrcRobotDrive
This class creates the FrcSwerve drive base subsystem that consists of wheel motors and related objects for driving a swerve robot.
  • Field Details

  • Constructor Details

    • FrcSwerveDrive

      public FrcSwerveDrive(FrcSwerveDrive.SwerveInfo swerveInfo)
      Constructor: Create an instance of the object.
      Parameters:
      swerveInfo - specifies the Swerve Robot Info.
  • Method Details

    • setSteerAngle

      public void setSteerAngle(double angle, boolean optimize, boolean hold)
      This method sets the steering angle of all swerve modules.
      Parameters:
      angle - specifies the steer angle.
      optimize - specifies true to optimize (only turns within +/- 90 degrees), false otherwse.
      hold - specifies true to hold the angle, false otherwise.
    • setXModeEnabled

      public void setXModeEnabled(String owner, boolean enabled)
      This method set all the wheels into an X configuration so that nobody can bump us out of position. If owner is specifies, it will acquire execlusive ownership of the drivebase on behalf of the specified owner. On disable, it will release the ownership.
      Parameters:
      owner - specifies the ID string of the caller for checking ownership, can be null if caller is not ownership aware.
      enabled - specifies true to enable anti-defense mode, false to disable.
    • displaySteerZeroCalibration

      public int displaySteerZeroCalibration(int lineNum)
      This method displays the steer zero calibration progress to the dashboard.
      Parameters:
      lineNum - specifies the starting line number to display the info on the dashboard.
      Returns:
      updated line number to the next available line on the dashboard.
    • startSteeringCalibration

      public void startSteeringCalibration()
      This method starts the steering calibration.
    • stopSteeringCalibration

      public void stopSteeringCalibration()
      This method stops the steering calibration and saves the calibration data to a file.
    • runSteeringCalibration

      public void runSteeringCalibration()
      This method is called periodically to sample the steer encoders for averaging the zero position data.
    • saveSteeringCalibrationData

      public void saveSteeringCalibrationData(double[] zeros)
      This method saves the calibration data to a file on the Robot Controller.
      Parameters:
      zeros - specifies the steering zero calibration data to be saved.
    • readSteeringCalibrationData

      public double[] readSteeringCalibrationData()
      This method reads the steering zero calibration data from the calibration data file.
      Returns:
      calibration data of all four swerve modules.
    • setModuleStates

      public void setModuleStates(edu.wpi.first.math.kinematics.SwerveModuleState[] desiredStates)
    • getModulePositions

      public edu.wpi.first.math.kinematics.SwerveModulePosition[] getModulePositions()
    • getPose

      public edu.wpi.first.math.geometry.Pose2d getPose()
    • setPose

      public void setPose(edu.wpi.first.math.geometry.Pose2d pose)
    • getHeading

      public edu.wpi.first.math.geometry.Rotation2d getHeading()
    • setHeading

      public void setHeading(edu.wpi.first.math.geometry.Rotation2d heading)
    • zeroHeading

      public void zeroHeading()
    • getGyroAngle

      public edu.wpi.first.math.geometry.Rotation2d getGyroAngle()
    • periodic

      public void periodic()