Package org.team1126.lib.swerve
Class SwerveAPI
java.lang.Object
org.team1126.lib.swerve.SwerveAPI
- All Implemented Interfaces:
AutoCloseable,Tunables.Tunable
An implementation of a swerve drivetrain, with support for various hardware configurations.
Includes features such as high frequency odometry, a custom ratelimiter to improve driver control while also reducing wheel scrub, and built-in support for tuning the drivetrain's configuration live via NetworkTables.
-
Field Summary
Fields -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionvoidaddVisionMeasurements(VisionMeasurement... measurements) Adds vision measurements to the pose estimator.voidapplyAssistedDriverInput(double x, double y, double angular, edu.wpi.first.math.kinematics.ChassisSpeeds assist, Perspective perspective, boolean discretize, boolean ratelimit) Drives using inputs from the driver's controller, with a specified additional chassis velocity.voidapplyDriverInput(double x, double y, double angular, Perspective perspective, boolean discretize, boolean ratelimit) Drives using inputs from the driver's controller.voidapplySpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds speeds, Perspective perspective, boolean discretize, boolean ratelimit) Drives using chassis speeds.voidapplyStates(edu.wpi.first.math.kinematics.SwerveModuleState[] states) Drives using module states.voidapplyStop(boolean lock) Drives the modules to stop the robot from moving.voidapplyVoltage(double voltage, edu.wpi.first.math.geometry.Rotation2d angle) Drives the robot using open-loop voltage.edu.wpi.first.math.kinematics.ChassisSpeedscalculateDriverSpeeds(double x, double y, double angular) Utility method for converting driver input to chassis speeds.voidclose()voidinitTunable(TunableTable table) Initializes the object to be tuned.voidrefresh()Refreshes inputs from all swerve hardware.voidresetPose(edu.wpi.first.math.geometry.Pose2d pose) Resets the pose of the robot, inherently seeding field-relative movement.voidsetBrakeMode(boolean move, boolean turn) Sets motor brake modes.voidtareRotation(Perspective perspective) Tares the rotation of the robot.
-
Field Details
-
state
-
config
-
-
Constructor Details
-
SwerveAPI
Create the drivetrain.- Parameters:
config- The drivetrain's config.
-
-
Method Details
-
refresh
public void refresh()Refreshes inputs from all swerve hardware. This must be called periodically in order for the API to function. Typically, this method is called at the start of the swerve subsystem'speriodic()method. -
addVisionMeasurements
Adds vision measurements to the pose estimator.- Parameters:
measurements- Vision measurements to apply to the pose estimator.
-
resetPose
public void resetPose(edu.wpi.first.math.geometry.Pose2d pose) Resets the pose of the robot, inherently seeding field-relative movement. Additionally, odometry and vision measurement history is flushed. This method is typically invoked at the start of a match to set the robot's position to the starting location of an autonomous mode. The supplied pose is expected to be blue origin relative.- Parameters:
pose- The new blue origin relative pose to apply to the pose estimator.
-
tareRotation
Tares the rotation of the robot. Useful for fixing an out of sync or drifting IMU. For most cases, a perspective ofPerspective.OPERATORis desirable.Perspective.ROBOTwill no-op.- Parameters:
perspective- The perspective to tare the rotation to.
-
calculateDriverSpeeds
public edu.wpi.first.math.kinematics.ChassisSpeeds calculateDriverSpeeds(double x, double y, double angular) Utility method for converting driver input to chassis speeds. Thexandyparameters expect the controller's NED (north-east-down) convention, and will automatically convert to WPILib's typical NWU (north-west-up) convention when calculating chassis speeds.- Parameters:
x- The X value of the driver's joystick, from[-1.0, 1.0].y- The Y value of the driver's joystick, from[-1.0, 1.0].angular- The CCW+ angular speed to apply, from[-1.0, 1.0].
-
applyDriverInput
public void applyDriverInput(double x, double y, double angular, Perspective perspective, boolean discretize, boolean ratelimit) Drives using inputs from the driver's controller. Thexandyparameters expect the controller's NED (north-east-down) convention, and will automatically convert to WPILib's typical NWU (north-west-up) convention when applying chassis speeds.- Parameters:
x- The X value of the driver's joystick, from[-1.0, 1.0].y- The Y value of the driver's joystick, from[-1.0, 1.0].angular- The CCW+ angular speed to apply, from[-1.0, 1.0].perspective- The forward perspective for the chassis speeds.discretize- If the generated speeds should be discretized.ratelimit- If the robot's acceleration should be constrained.
-
applyAssistedDriverInput
public void applyAssistedDriverInput(double x, double y, double angular, edu.wpi.first.math.kinematics.ChassisSpeeds assist, Perspective perspective, boolean discretize, boolean ratelimit) Drives using inputs from the driver's controller, with a specified additional chassis velocity. Thexandyparameters expect the controller's NED (north-east-down) convention, and will automatically convert to WPILib's typical NWU (north-west-up) convention when applying chassis speeds.- Parameters:
x- The X value of the driver's joystick, from[-1.0, 1.0].y- The Y value of the driver's joystick, from[-1.0, 1.0].angular- The CCW+ angular speed to apply, from[-1.0, 1.0].assist- Additional velocities to apply. Note that these speeds are relative to the provided perspective, and are still restricted by the ratelimiter if it is active.perspective- The forward perspective for the chassis speeds.discretize- If the generated speeds should be discretized.ratelimit- If the robot's acceleration should be constrained.
-
applySpeeds
public void applySpeeds(edu.wpi.first.math.kinematics.ChassisSpeeds speeds, Perspective perspective, boolean discretize, boolean ratelimit) Drives using chassis speeds.- Parameters:
speeds- The chassis speeds to apply. Note that the providedChassisSpeedsobject may be mutated.perspective- The forward perspective for the chassis speeds.discretize- If the speeds should be discretized.ratelimit- If the robot's acceleration should be constrained.
-
applyStates
public void applyStates(edu.wpi.first.math.kinematics.SwerveModuleState[] states) Drives using module states.- Parameters:
states- The states to apply.
-
applyStop
public void applyStop(boolean lock) Drives the modules to stop the robot from moving.- Parameters:
lock- If the wheels should be driven to an X formation to stop the robot from being pushed.
-
applyVoltage
public void applyVoltage(double voltage, edu.wpi.first.math.geometry.Rotation2d angle) Drives the robot using open-loop voltage. Intended for characterization. Plumbing for recording device voltage via their Java API is intentionally unavailable, as GC pressure and CAN latency will result in inaccurate data. Use Phoenix Signal Logging or REV's StatusLogger instead.- Parameters:
voltage- The voltage to apply to the move motors.angle- The robot-relative angle to apply to the turn motors.
-
setBrakeMode
public void setBrakeMode(boolean move, boolean turn) Sets motor brake modes.- Parameters:
move- If the move motors should have brake mode enabled.turn- If the turn motors should have brake mode enabled.
-
initTunable
Description copied from interface:Tunables.TunableInitializes the object to be tuned. This method is called when adding the object to aTunableTable.- Specified by:
initTunablein interfaceTunables.Tunable- Parameters:
table- The table the object is being added to.
-
close
public void close()- Specified by:
closein interfaceAutoCloseable
-