Class TorqueSwerveModule2022

java.lang.Object
org.texastorque.torquelib.modules.base.TorqueSwerveModule
org.texastorque.torquelib.modules.TorqueSwerveModule2022

public final class TorqueSwerveModule2022 extends TorqueSwerveModule
Super cool flipped swerve module built in 2023 by Abishek. https://drive.google.com/file/d/1bvgo75gqLzoerBIEtEObXep_6gpac6mZ/view?usp=sharing https://drive.google.com/file/d/1q4cmx3Ntscfynn_1Tc8W9VAqR9Tgn0NT/view?usp=sharing The module uses a Rev NEO for drive and rotation control. It uses a CTRE Cancoder positioned 1:1 with the wheel rotation. The code is kinda based off the FRC 1706 swerve module. Cancoder docs: https://api.ctr-electronics.com/phoenix/release/java/com/ctre/phoenix/sensors/CANCoder.html The rotation of the modules is [0, 2π) radians, with 0 being straight ahead (I think). 0 or 2π ↑ π/2 ← * → 3π/2 ↓ π
  • Field Details

    • staticOffset

      public final double staticOffset
    • name

      public final String name
    • useSmartDrive

      public boolean useSmartDrive
    • useCancoder

      public boolean useCancoder
  • Constructor Details

  • Method Details

    • setDesiredState

      public void setDesiredState(edu.wpi.first.math.kinematics.SwerveModuleState state)
      Specified by:
      setDesiredState in class TorqueSwerveModule
    • getState

      public edu.wpi.first.math.kinematics.SwerveModuleState getState()
      Specified by:
      getState in class TorqueSwerveModule
    • getPosition

      public edu.wpi.first.math.kinematics.SwerveModulePosition getPosition()
    • getRotation

      public edu.wpi.first.math.geometry.Rotation2d getRotation()
      Specified by:
      getRotation in class TorqueSwerveModule
    • stop

      public void stop()
    • zero

      public void zero()
    • normalize

      public static void normalize(edu.wpi.first.math.kinematics.SwerveModuleState[] states, double max)
      Normalizes drive speeds to never exceed a specified max.
      Parameters:
      states - The swerve module states, this is mutated!
      max - Maximum translational speed.