Class SwerveSteeringSubsystem

All Implemented Interfaces:
Sendable, Subsystem, DataFrameRefreshable, SupportsSetpointLock, IPropertySupport

public class SwerveSteeringSubsystem extends BaseSetpointSubsystem<Double>
  • Constructor Details

  • Method Details

    • getLabel

      public String getLabel()
    • getPrefix

      public String getPrefix()
      Specified by:
      getPrefix in interface IPropertySupport
      Overrides:
      getPrefix in class BaseSubsystem
    • getCurrentValue

      public Double getCurrentValue()
      Gets current angle in degrees
      Specified by:
      getCurrentValue in class BaseSetpointSubsystem<Double>
    • getCurrentRotation

      public Rotation2d getCurrentRotation()
      Gets current angle as a Rotation2d
    • getTargetValue

      public Double getTargetValue()
      Gets target angle in degrees
      Specified by:
      getTargetValue in class BaseSetpointSubsystem<Double>
    • setTargetValue

      public void setTargetValue(Double value)
      Sets target angle in degrees
      Specified by:
      setTargetValue in class BaseSetpointSubsystem<Double>
    • setPower

      public void setPower(double power)
      Sets the output power of the motor.
      Specified by:
      setPower in class BaseSetpointSubsystem<Double>
      Parameters:
      power - The power value, between -1 and 1.
    • isCalibrated

      public boolean isCalibrated()
      Specified by:
      isCalibrated in class BaseSetpointSubsystem<Double>
    • calibrateHere

      public void calibrateHere()
      Mark the current encoder position as facing forward (0 degrees)
    • calibrateMotorControllerPositionFromCanCoder

      public void calibrateMotorControllerPositionFromCanCoder()
      Reset the SparkMax encoder position based on the CanCoder measurement. This should only be called when the mechanism is stationary.
    • getVelocity

      public AngularVelocity getVelocity()
    • isMotorControllerDriftTooHigh

      public static boolean isMotorControllerDriftTooHigh(Angle currentCanCoderPosition, Angle currentMotorControllerPosition, double maxDelta)
    • getMotorController

      public XCANMotorController getMotorController()
    • getEncoder

      public XCANCoder getEncoder()
    • getBestEncoderPosition

      public Angle getBestEncoderPosition()
      Gets the current position of the mechanism using the best available encoder.
      Returns:
      The position in degrees.
    • getAbsoluteEncoderPosition

      public Angle getAbsoluteEncoderPosition()
      Gets the reported position of the CANCoder.
      Returns:
      The position of the CANCoder.
    • getMotorControllerEncoderPosition

      public Angle getMotorControllerEncoderPosition()
      Gets the reported position of the encoder on the NEO motor.
      Returns:
      The position of the encoder on the NEO motor.
    • calculatePower

      public double calculatePower()
      Calculate the target motor power using software PID.
      Returns:
      The target power required to approach our setpoint.
    • resetPid

      public void resetPid()
      Reset the software PID.
    • isUsingMotorControllerPid

      public boolean isUsingMotorControllerPid()
      Gets a flag indicating whether we are using the motor controller's PID or software PID.
      Returns:
      true if using motor controller's PID.
    • setMotorControllerPidTarget

      public void setMotorControllerPidTarget()
      Calculates the nearest position on the motor encoder to targetDegrees and sets the controller's PID target.
    • areTwoTargetsEquivalent

      protected boolean areTwoTargetsEquivalent(Double target1, Double target2)
      Specified by:
      areTwoTargetsEquivalent in class BaseSetpointSubsystem<Double>
    • periodic

      public void periodic()
      Description copied from class: BaseSubsystem
      This method is called on each CommandScheduler loop.
      Specified by:
      periodic in interface Subsystem
      Overrides:
      periodic in class BaseSubsystem
    • refreshDataFrame

      public void refreshDataFrame()
      Description copied from interface: DataFrameRefreshable
      Consumes and processes inputs from the device or subsystem.
      Specified by:
      refreshDataFrame in interface DataFrameRefreshable
      Overrides:
      refreshDataFrame in class BaseSubsystem