Package ftclib.drivebase
Class FtcSwerveDrive
java.lang.Object
ftclib.drivebase.FtcRobotDrive
ftclib.drivebase.FtcSwerveDrive
This class creates the FtcSwerve drive base subsystem that consists of wheel motors and related objects for
driving a swerve robot.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic class
This class contains Swerve Robot Info.Nested classes/interfaces inherited from class ftclib.drivebase.FtcRobotDrive
FtcRobotDrive.RobotInfo, FtcRobotDrive.VisionInfo
-
Field Summary
FieldsModifier and TypeFieldDescriptionprivate final FtcDashboard
private final String
final TrcEncoder[]
final TrcMotor[]
private int
private final double[]
final TrcSwerveModule[]
final TrcDbgTrace
private String
Fields inherited from class ftclib.drivebase.FtcRobotDrive
driveBase, driveMotors, gyro, INDEX_LEFT_BACK, INDEX_LEFT_CENTER, INDEX_LEFT_FRONT, INDEX_RIGHT_BACK, INDEX_RIGHT_CENTER, INDEX_RIGHT_FRONT, pidDrive, purePursuitDrive, robotInfo
-
Constructor Summary
ConstructorsConstructorDescriptionFtcSwerveDrive
(FtcSwerveDrive.SwerveInfo swerveInfo) Constructor: Create an instance of the object. -
Method Summary
Modifier and TypeMethodDescriptionprivate TrcEncoder[]
This method creates and configures all steer encoders.private TrcMotor[]
This method creates and configures all steer motors.private TrcSwerveModule[]
This method creates and configures all swerve modules.int
displaySteerZeroCalibration
(int lineNum) This method displays the steer zero calibration progress to the dashboard.double[]
This method reads the steering zero calibration data from the calibration data file.void
This method is called periodically to sample the steer encoders for averaging the zero position data.void
saveSteeringCalibrationData
(double[] zeros) This method saves the calibration data to a file on the Robot Controller.void
setSteerAngle
(double angle, boolean optimize, boolean hold) This method sets the steering angle of all swerve modules.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.void
This method starts the steering calibration.void
This method stops the steering calibration and saves the calibration data to a file.Methods inherited from class ftclib.drivebase.FtcRobotDrive
cancel, cancel, configDriveBase
-
Field Details
-
moduleName
-
tracer
-
swerveInfo
-
steerEncoders
-
steerMotors
-
swerveModules
-
dashboard
-
steerZeros
private final double[] steerZeros -
steerZeroCalibrationCount
private int steerZeroCalibrationCount -
xModeOwner
-
-
Constructor Details
-
FtcSwerveDrive
Constructor: Create an instance of the object.- Parameters:
swerveInfo
- specifies the Swerve Robot Info.
-
-
Method Details
-
createSteerEncoders
This method creates and configures all steer encoders.- Returns:
- an array of created steer encoders.
-
createSteerMotors
This method creates and configures all steer motors.- Returns:
- an array of created steer servos.
-
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
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.
-