Class FtcSwerveDrive

java.lang.Object
ftclib.drivebase.FtcRobotDrive
ftclib.drivebase.FtcSwerveDrive

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

    • moduleName

      private final String moduleName
    • tracer

      public final TrcDbgTrace tracer
    • swerveInfo

      public final FtcSwerveDrive.SwerveInfo swerveInfo
    • steerEncoders

      public final TrcEncoder[] steerEncoders
    • steerMotors

      public final TrcMotor[] steerMotors
    • swerveModules

      public final TrcSwerveModule[] swerveModules
    • dashboard

      private final FtcDashboard dashboard
    • steerZeros

      private final double[] steerZeros
    • steerZeroCalibrationCount

      private int steerZeroCalibrationCount
    • xModeOwner

      private String xModeOwner
  • Constructor Details

    • FtcSwerveDrive

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

    • createSteerEncoders

      private TrcEncoder[] createSteerEncoders()
      This method creates and configures all steer encoders.
      Returns:
      an array of created steer encoders.
    • createSteerMotors

      private TrcMotor[] createSteerMotors()
      This method creates and configures all steer motors.
      Returns:
      an array of created steer servos.
    • createSwerveModules

      private TrcSwerveModule[] createSwerveModules()
      This method creates and configures all swerve modules.
      Returns:
      an array of created swerve modules.
    • 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.