Package org.team1126.lib.swerve.hardware
Class SwerveEncoders.SwerveEncoder
java.lang.Object
org.team1126.lib.swerve.hardware.SwerveEncoders.SwerveEncoder
- All Implemented Interfaces:
AutoCloseable
- Enclosing class:
SwerveEncoders
A swerve module's absolute encoder.
All units are in rotations.
-
Nested Class Summary
Nested ClassesModifier and TypeClassDescriptionstatic interface(config, turnMotor) -> SwerveEncoderstatic final record -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionstatic SwerveEncoders.SwerveEncoderconstruct(SwerveEncoders.SwerveEncoder.Ctor ctor, SwerveConfig config, SwerveMotors.SwerveMotor turnMotor) Constructs a swerve encoder.getAPI()Returns the device's underlying API.abstract doubleGets the encoder's position in rotations.default List<com.ctre.phoenix6.BaseStatusSignal> Returns all Phoenix status signals in use by the hardware.Some motor controllers can be configured to use external encoders as a feedback device for closed-loop control.default booleanIf the device has encountered an error while reading inputs.Methods inherited from class java.lang.Object
clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, waitMethods inherited from interface java.lang.AutoCloseable
close
-
Constructor Details
-
SwerveEncoder
public SwerveEncoder()
-
-
Method Details
-
construct
public static SwerveEncoders.SwerveEncoder construct(SwerveEncoders.SwerveEncoder.Ctor ctor, SwerveConfig config, SwerveMotors.SwerveMotor turnMotor) Constructs a swerve encoder. Wraps to support simulation if applicable.- Parameters:
ctor- The encoder's constructor.config- The general swerve API configuration.turnMotor- The turn motor associated with the encoder's module.
-
getPosition
public abstract double getPosition()Gets the encoder's position in rotations. -
hookStatus
Some motor controllers can be configured to use external encoders as a feedback device for closed-loop control. This method returns aSwerveEncoders.SwerveEncoder.HookStatusthat specifies if the encoder's corresponding turn motor has been configured to return an absolute position via itsgetPosition()method (SwerveEncoders.SwerveEncoder.HookStatus.readMotor), and/or accept an absolute position when setting its closed loop position target (SwerveEncoders.SwerveEncoder.HookStatus.applyAbsolute). -
getAPI
Object getAPI()Returns the device's underlying API. -
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 callingSwerveAPI.refresh(). -
readError
default boolean readError()If the device has encountered an error while reading inputs.
-