Class SN_SwerveModule
java.lang.Object
edu.wpi.first.wpilibj2.command.SubsystemBase
com.frcteam3255.components.swerve.SN_SwerveModule
- All Implemented Interfaces:
edu.wpi.first.util.sendable.Sendable,edu.wpi.first.wpilibj2.command.Subsystem
public class SN_SwerveModule
extends edu.wpi.first.wpilibj2.command.SubsystemBase
-
Field Summary
FieldsModifier and TypeFieldDescriptionstatic com.ctre.phoenix6.configs.CANcoderConfigurationstatic com.ctre.phoenix6.configs.TalonFXConfigurationcom.ctre.phoenix6.hardware.TalonFXstatic booleanstatic doublestatic doubleintstatic com.ctre.phoenix6.configs.TalonFXConfigurationcom.ctre.phoenix6.hardware.TalonFXstatic double -
Constructor Summary
ConstructorsConstructorDescriptionSN_SwerveModule(int moduleNumber, int driveMotorID, int steerMotorID, int absoluteEncoderID, double absoluteEncoderOffset, String CANBusName) This subsystem represents 1 Swerve Module. -
Method Summary
Modifier and TypeMethodDescriptionvoiddoubleGet the current position, with the offset applied, of the module's absolute encoder.edu.wpi.first.math.kinematics.SwerveModuleStateGet the current state (velocity, angle) of the module.edu.wpi.first.math.kinematics.SwerveModuleStateGet the last desired state (velocity, angle) of the module.edu.wpi.first.math.kinematics.SwerveModulePositionGet the current position (distance traveled, angle) of the module.doubleGet the current raw position (no offset applied) of the module's absolute encoder.voidNeutral the drive motor output.voidReset the drive motor's encoder to 0.voidResets the steer motor's encoder to the absolute encoder's offset value.voidsetModuleState(edu.wpi.first.math.kinematics.SwerveModuleState desiredState, boolean isOpenLoop, boolean steerInPlace) Sets the current state (velocity and position) of the module.Methods inherited from class edu.wpi.first.wpilibj2.command.SubsystemBase
addChild, getName, getSubsystem, initSendable, setName, setSubsystemMethods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface edu.wpi.first.wpilibj2.command.Subsystem
defer, getCurrentCommand, getDefaultCommand, periodic, register, removeDefaultCommand, run, runEnd, runOnce, setDefaultCommand, simulationPeriodic, startEnd, startRun
-
Field Details
-
driveMotor
public com.ctre.phoenix6.hardware.TalonFX driveMotor -
steerMotor
public com.ctre.phoenix6.hardware.TalonFX steerMotor -
moduleNumber
public int moduleNumber -
driveConfiguration
public static com.ctre.phoenix6.configs.TalonFXConfiguration driveConfiguration -
steerConfiguration
public static com.ctre.phoenix6.configs.TalonFXConfiguration steerConfiguration -
cancoderConfiguration
public static com.ctre.phoenix6.configs.CANcoderConfiguration cancoderConfiguration -
minimumSteerSpeedPercent
public static double minimumSteerSpeedPercent -
wheelCircumference
public static double wheelCircumference -
maxModuleSpeedMeters
public static double maxModuleSpeedMeters -
isSimulation
public static boolean isSimulation
-
-
Constructor Details
-
SN_SwerveModule
public SN_SwerveModule(int moduleNumber, int driveMotorID, int steerMotorID, int absoluteEncoderID, double absoluteEncoderOffset, String CANBusName) This subsystem represents 1 Swerve Module. In order to use SN_SuperSwerve, you must create an array of 4 of these.- Parameters:
moduleNumber- The number of the module. Typically, these are 0 to 3. 0 = Front Left, 1 = Front Right, 2 = Back Left, 3 = Back RightdriveMotorID- The CAN id of the drive motorsteerMotorID- The CAN id of the steer motorabsoluteEncoderID- The CAN id of the CANcoderabsoluteEncoderOffset- The offset of the CANcoder in rotations. This is typically obtained by aligning all of the wheels in the appropriate direction and then copying the Raw Absolute encoder value.CANBusName- The name of the CANBus that the module is connected to.
-
-
Method Details
-
configure
public void configure() -
getRawAbsoluteEncoder
public double getRawAbsoluteEncoder()Get the current raw position (no offset applied) of the module's absolute encoder. This value will NOT match the physical angle of the wheel.- Returns:
- Position in rotations
-
getAbsoluteEncoder
public double getAbsoluteEncoder()Get the current position, with the offset applied, of the module's absolute encoder. This value should match the physical angle of the module's wheel.- Returns:
- Position in rotations, with the module's offset
-
resetSteerMotorToAbsolute
public void resetSteerMotorToAbsolute()Resets the steer motor's encoder to the absolute encoder's offset value. The drive motor is not reset here because the absolute encoder does not record it's rotation. -
resetDriveMotorEncoder
public void resetDriveMotorEncoder()Reset the drive motor's encoder to 0. -
getActualModuleState
public edu.wpi.first.math.kinematics.SwerveModuleState getActualModuleState()Get the current state (velocity, angle) of the module.- Returns:
- Module's SwerveModuleState (velocity, angle)
-
getDesiredModuleState
public edu.wpi.first.math.kinematics.SwerveModuleState getDesiredModuleState()Get the last desired state (velocity, angle) of the module.- Returns:
- Module's Desired SwerveModuleState (velocity, angle)
-
getModulePosition
public edu.wpi.first.math.kinematics.SwerveModulePosition getModulePosition()Get the current position (distance traveled, angle) of the module. In simulation, this will return a simulated value.- Returns:
- Module's SwerveModulePosition (distance, angle)
-
neutralDriveOutput
public void neutralDriveOutput()Neutral the drive motor output. -
setModuleState
public void setModuleState(edu.wpi.first.math.kinematics.SwerveModuleState desiredState, boolean isOpenLoop, boolean steerInPlace) Sets the current state (velocity and position) of the module. Given values are optimized so that the module can travel the least distance to achieve the desired value.- Parameters:
desiredState- Desired velocity and angle of the moduleisOpenLoop- Is the module being set based on open loop or closed loop controlsteerInPlace- If the module can be rotated in place
-