Package frc.team_8840_lib.controllers
Class SwerveModule
java.lang.Object
frc.team_8840_lib.controllers.SwerveModule
-
Nested Class Summary
Nested Classes -
Constructor Summary
ConstructorsConstructorDescriptionSwerveModule(SwerveSettings settings, ModuleConfig config, SwerveModule.Position position) Creates a new swerve module -
Method Summary
Modifier and TypeMethodDescriptionvoidConfigures the CANCoder settings (ran through the IOCANCoder class, but is the same as what you would do with a normal CANCoder)Configure the settings of the motorsedu.wpi.first.math.geometry.Rotation2dGets the absolute angle (angle of the encoder) of the moduleedu.wpi.first.math.geometry.Rotation2dgetAngle()Gets the current angle of the moduleedu.wpi.first.math.geometry.Rotation2dGets the desired angle of the moduleedu.wpi.first.math.kinematics.SwerveModulePositionGets the current position of the modulegetSpeed()Gets the current speed of the moduleedu.wpi.first.math.kinematics.SwerveModuleStategetState()Gets the current state of the modulebooleanReturns if the initialized flag has been enabled.Sets the angle of the turn encoder to the absolute angle subtracted by the offset so forward is 0°voidsetAngle(edu.wpi.first.math.geometry.Rotation2d angle, boolean ignoreAngleLimit) Sets the angle of the turn motorvoidsetDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state, boolean openLoop) Sets the desired state of the module (speed and angle) with automatic angle optimizationvoidsetDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state, boolean openLoop, boolean runOptimization) Sets the desired state of the module (speed and angle)voidsetNeoCANStatusFrames(com.revrobotics.CANSparkMax m_motor, int CANStatus0, int CANStatus1, int CANStatus2, int CANStatus3, int CANStatus4) Sets the NEO CAN Status FramesvoidSets the speed of the drive motorvoidSets the speed of the drive motorvoidstop()Sets the speed of the drive motor to 0
-
Constructor Details
-
SwerveModule
Creates a new swerve module- Parameters:
settings- The settings for the swerve drive itself (gyro reversed, etc)config- The config for the swerve module (motor IDs, encoder IDs, etc)position- The position of the swerve module (front left, front right, back left, back right)
-
-
Method Details
-
configCANCoder
public void configCANCoder()Configures the CANCoder settings (ran through the IOCANCoder class, but is the same as what you would do with a normal CANCoder) -
configMotors
Configure the settings of the motors- Returns:
- a promise that will be resolved (finished) when the motors are ready
-
resetToAbsolute
Sets the angle of the turn encoder to the absolute angle subtracted by the offset so forward is 0°- Returns:
- A promise that resolves (finishes) when the turn encoder is successfully set to the absolute angle subtracted by the offset
-
setNeoCANStatusFrames
public void setNeoCANStatusFrames(com.revrobotics.CANSparkMax m_motor, int CANStatus0, int CANStatus1, int CANStatus2, int CANStatus3, int CANStatus4) Sets the NEO CAN Status Frames- Parameters:
m_motor- The motor to set the status frames forCANStatus0- The status frame 0 periodCANStatus1- The status frame 1 periodCANStatus2- The status frame 2 periodCANStatus3- The status frame 3 periodCANStatus4- The status frame 4 period
-
setSpeed
Sets the speed of the drive motor- Parameters:
speed- The speed to set the motor to. Assume the units are per secondopenLoop- Whether or not to use open loop control
-
setSpeed
Sets the speed of the drive motor- Parameters:
speed- The speed to set the motor to. Assume the units are per secondopenLoop- Whether or not to use open loop controlignoreSpeedFlags- Whether or not to ignore the speed flags
-
setAngle
public void setAngle(edu.wpi.first.math.geometry.Rotation2d angle, boolean ignoreAngleLimit) Sets the angle of the turn motor- Parameters:
angle- The angle to set the motor toignoreAngleLimit- Whether or not to ignore the angle movement limit (used for preventing jolts/snapping and damage to the module)
-
setDesiredState
public void setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state, boolean openLoop) Sets the desired state of the module (speed and angle) with automatic angle optimization- Parameters:
state- The state to set the module toopenLoop- Whether or not to use open loop control
-
setDesiredState
public void setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state, boolean openLoop, boolean runOptimization) Sets the desired state of the module (speed and angle)- Parameters:
state- The state to set the module toopenLoop- Whether or not to use open loop controlrunOptimization- Whether or not to run the optimization algorithm on the angle
-
stop
public void stop()Sets the speed of the drive motor to 0 -
getAbsoluteAngle
public edu.wpi.first.math.geometry.Rotation2d getAbsoluteAngle()Gets the absolute angle (angle of the encoder) of the module- Returns:
- The absolute angle/angle of the encoder of the module
-
getState
public edu.wpi.first.math.kinematics.SwerveModuleState getState()Gets the current state of the module- Returns:
- The swerve module state derived through the internal encoder velocity and the rotation of the module
-
getAngle
public edu.wpi.first.math.geometry.Rotation2d getAngle()Gets the current angle of the module- Returns:
- The current angle of the module
-
getDesiredAngle
public edu.wpi.first.math.geometry.Rotation2d getDesiredAngle()Gets the desired angle of the module- Returns:
- The desired angle of the module
-
getSpeed
Gets the current speed of the module- Returns:
- The current speed of the module. Assume these units are per seconds.
-
getPosition
public edu.wpi.first.math.kinematics.SwerveModulePosition getPosition()Gets the current position of the module- Returns:
- The current position of the module derived through the internal encoder position and the rotation of the module
-
initalized
public boolean initalized()Returns if the initialized flag has been enabled.
-