Class SwerveModule
This class handles the hardware devices and configures them for swerve module operation using the Phoenix 6 API.
This class constructs hardware devices internally, so the user only specifies the constants (IDs, PID gains, gear ratios, etc). Getters for these hardware devices are available.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic enum
All possible control requests for the module drive motor.static class
Contains everything the swerve module needs to apply a request.static enum
All possible control requests for the module steer motor. -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected static final int
Number of times to attempt config applies.protected final int
ID of the native drivetrain instance, used for JNI calls.protected final SwerveJNI
JNI instance to use for non-static JNI calls.protected final int
Index of this module in the native drivetrain, used for JNI calls. -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModule
(SwerveModuleConstants constants, String canbusName, int drivetrainId, int index) Construct a SwerveModule with the specified constants. -
Method Summary
Modifier and TypeMethodDescriptionvoid
apply
(ControlRequest driveRequest, ControlRequest steerRequest) Controls this module using the specified drive and steer control requests.void
apply
(SwerveModule.ModuleRequest moduleRequest) Applies the desired SwerveModuleState to this module.final SwerveModulePosition
Gets the last cached swerve module position.final CANcoder
Gets this module's CANcoder reference.final SwerveModuleState
Get the current state of the module.final TalonFX
Gets this module's Drive Motor TalonFX reference.final SwerveModulePosition
getPosition
(boolean refresh) Gets the state of this module and passes it back as a SwerveModulePosition object with latency compensated values.final TalonFX
Gets this module's Steer Motor TalonFX reference.final SwerveModuleState
Get the target state of the module.void
Resets this module's drive motor position to 0 rotations.
-
Field Details
-
kNumConfigAttempts
Number of times to attempt config applies.- See Also:
-
m_drivetrainId
ID of the native drivetrain instance, used for JNI calls. -
m_moduleIdx
Index of this module in the native drivetrain, used for JNI calls. -
m_jni
JNI instance to use for non-static JNI calls. This object is not thread-safe.
-
-
Constructor Details
-
SwerveModule
public SwerveModule(SwerveModuleConstants constants, String canbusName, int drivetrainId, int index) Construct a SwerveModule with the specified constants.- Parameters:
constants
- Constants used to construct the modulecanbusName
- The name of the CAN bus this module is ondrivetrainId
- ID of the swerve drivetrainindex
- Index of this swerve module
-
-
Method Details
-
apply
Applies the desired SwerveModuleState to this module.- Parameters:
moduleRequest
- The request to apply to this module
-
apply
Controls this module using the specified drive and steer control requests. This is intended only to be used for characterization of the robot; do not use this for normal use.- Parameters:
driveRequest
- The control request to apply to the drive motorsteerRequest
- The control request to apply to the steer motor
-
getPosition
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compensated values.This function is blocking when it performs a refresh.
- Parameters:
refresh
- True if the signals should be refreshed- Returns:
- SwerveModulePosition containing this module's state
-
getCachedPosition
Gets the last cached swerve module position. This differs fromgetPosition(boolean)
in that it will not perform any latency compensation or refresh the signals.- Returns:
- Last cached SwerveModulePosition
-
getCurrentState
Get the current state of the module.This is typically used for telemetry, as the SwerveModulePosition is used for odometry.
- Returns:
- Current state of the module
-
getTargetState
Get the target state of the module.This is typically used for telemetry.
- Returns:
- Target state of the module
-
resetPosition
Resets this module's drive motor position to 0 rotations. -
getDriveMotor
Gets this module's Drive Motor TalonFX reference.This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
- This module's Drive Motor reference
-
getSteerMotor
Gets this module's Steer Motor TalonFX reference.This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
- This module's Steer Motor reference
-
getCANcoder
Gets this module's CANcoder reference.This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
- Returns:
- This module's CANcoder reference
-