Class SwerveModule

java.lang.Object
frc.team_8840_lib.controllers.SwerveModule

public class SwerveModule extends Object
  • Nested Class Summary

    Nested Classes
    Modifier and Type
    Class
    Description
    static enum 
     
  • Constructor Summary

    Constructors
    Constructor
    Description
    Creates a new swerve module
  • Method Summary

    Modifier and Type
    Method
    Description
    void
    Configures 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 motors
    edu.wpi.first.math.geometry.Rotation2d
    Gets the absolute angle (angle of the encoder) of the module
    edu.wpi.first.math.geometry.Rotation2d
    Gets the current angle of the module
    edu.wpi.first.math.geometry.Rotation2d
    Gets the desired angle of the module
    edu.wpi.first.math.kinematics.SwerveModulePosition
    Gets the current position of the module
    Gets the current speed of the module
    edu.wpi.first.math.kinematics.SwerveModuleState
    Gets the current state of the module
    boolean
    Returns 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°
    void
    setAngle(edu.wpi.first.math.geometry.Rotation2d angle, boolean ignoreAngleLimit)
    Sets the angle of the turn motor
    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
    void
    setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state, boolean openLoop, boolean runOptimization)
    Sets the desired state of the module (speed and angle)
    void
    setNeoCANStatusFrames(com.revrobotics.CANSparkMax m_motor, int CANStatus0, int CANStatus1, int CANStatus2, int CANStatus3, int CANStatus4)
    Sets the NEO CAN Status Frames
    void
    setSpeed(Unit speed, boolean openLoop)
    Sets the speed of the drive motor
    void
    setSpeed(Unit speed, boolean openLoop, boolean ignoreSpeedFlags)
    Sets the speed of the drive motor
    void
    Sets the speed of the drive motor to 0

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • SwerveModule

      public SwerveModule(SwerveSettings settings, ModuleConfig config, SwerveModule.Position position)
      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

      public Promise configMotors()
      Configure the settings of the motors
      Returns:
      a promise that will be resolved (finished) when the motors are ready
    • resetToAbsolute

      public Promise 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 for
      CANStatus0 - The status frame 0 period
      CANStatus1 - The status frame 1 period
      CANStatus2 - The status frame 2 period
      CANStatus3 - The status frame 3 period
      CANStatus4 - The status frame 4 period
    • setSpeed

      public void setSpeed(Unit speed, boolean openLoop)
      Sets the speed of the drive motor
      Parameters:
      speed - The speed to set the motor to. Assume the units are per second
      openLoop - Whether or not to use open loop control
    • setSpeed

      public void setSpeed(Unit speed, boolean openLoop, boolean ignoreSpeedFlags)
      Sets the speed of the drive motor
      Parameters:
      speed - The speed to set the motor to. Assume the units are per second
      openLoop - Whether or not to use open loop control
      ignoreSpeedFlags - 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 to
      ignoreAngleLimit - 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 to
      openLoop - 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 to
      openLoop - Whether or not to use open loop control
      runOptimization - 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

      public Unit 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.