Class SwerveMotors.SwerveMotor

java.lang.Object
org.team1126.lib.swerve.hardware.SwerveMotors.SwerveMotor
All Implemented Interfaces:
AutoCloseable
Enclosing class:
SwerveMotors

public abstract static class SwerveMotors.SwerveMotor extends Object
A swerve motor. All units are in rotations.
  • Constructor Details

    • SwerveMotor

      public SwerveMotor()
  • Method Details

    • construct

      public static SwerveMotors.SwerveMotor construct(SwerveMotors.SwerveMotor.Ctor ctor, SwerveConfig config, boolean isMoveMotor)
      Constructs a swerve motor. Wraps to support simulation if applicable.
      Parameters:
      ctor - The motor's constructor.
      config - The general swerve API configuration.
      isMoveMotor - true if the motor is a move motor.
    • getPosition

      public abstract double getPosition()
      Gets the motor's position in rotations.
    • setPosition

      public abstract void setPosition(double position)
      Sets the motor's closed-loop position target.
      Parameters:
      position - The target position in rotations.
    • getVelocity

      public abstract double getVelocity()
      Gets the motor's velocity in rotations/second.
    • setVelocity

      public abstract void setVelocity(double velocity)
      Sets the motor's closed-loop velocity target.
      Parameters:
      velocity - The target velocity in rotations/second.
    • setVoltage

      public abstract void setVoltage(double voltage)
      Sets the motor's output voltage.
      Parameters:
      voltage - The voltage to apply.
    • reapplyGains

      public abstract void reapplyGains()
      Re-applies PID and FF gains from the swerve config. Used for setting new gains after the config has been mutated. This is likely a blocking operation.
    • reapplyBrakeMode

      public abstract void reapplyBrakeMode()
      Configures the motor's brake mode from the swerve config. Used for setting a new value after the config has been mutated. This is likely a blocking operation.
    • getAPI

      Object getAPI()
      Returns the device's underlying API.
    • getSignals

      default List<com.ctre.phoenix6.BaseStatusSignal> getSignals()
      Returns all Phoenix status signals in use by the hardware. Phoenix hardware should not invoke .refresh() on their status signals in their implementations. This method is required for the odometry thread to register signals to be refreshed automatically. Because signals are not thread safe, all returned signals should also be cloned in their initialization as to not interfere with telemetry, which is invoked on the main thread. The exception to this rule is IMU pitch and roll values, as they are only measured synchronously when calling SwerveAPI.refresh().
    • readError

      default boolean readError()
      If the device has encountered an error while reading inputs.