Engu

class Engu(id: Int, canbus: CANBus = CANBus.roboRIO()) : CANcoder

Enhanced CANcoder wrapper class with simplified configuration and utility methods.

Provides convenient methods for common encoder operations like angle reading, offset calibration, and unit conversions specifically useful for swerve drive modules.

Usage Examples:

// Basic setup
val encoder = Engu(1)

// Configure with offset and direction
encoder.configure {
MagnetSensor.apply {
SensorDirection = SensorDirectionValue.CounterClockwise_Positive
MagnetOffset = 0.25
}
}

// Get angle as Rotation2d
val angle = encoder.rotation

// Get position in rotations
val rotations = encoder.rotations

// Get position in degrees
val degrees = encoder.degrees

Constructors

Link copied to clipboard
constructor(id: Int, canbus: CANBus = CANBus.roboRIO())

Properties

Link copied to clipboard
val absolutePosition: StatusSignal<Angle?>?
Link copied to clipboard
val angle: Angle

Gets the absolute position as a measured angle.

Link copied to clipboard
val angularVelocity: AngularVelocity

Gets the angular velocity as a measured value.

Link copied to clipboard
val appliedControl: ControlRequest?
Link copied to clipboard
lateinit var configuration: CANcoderConfiguration

Holds the last CANcoderConfiguration applied to this CANcoder. This property is updated whenever the configure method is called. It allows retrieval of the configuration settings for inspection or reuse.

Link copied to clipboard
val configurator: CANcoderConfigurator?
Link copied to clipboard

Gets the absolute position in degrees (0.0 to 360.0).

Link copied to clipboard
Link copied to clipboard
Link copied to clipboard
val fault_BadMagnet: StatusSignal<Boolean?>?
Link copied to clipboard
val fault_BootDuringEnable: StatusSignal<Boolean?>?
Link copied to clipboard
val fault_Hardware: StatusSignal<Boolean?>?
Link copied to clipboard
val fault_Undervoltage: StatusSignal<Boolean?>?
Link copied to clipboard
Link copied to clipboard
val faultField: StatusSignal<Int?>?
Link copied to clipboard
Link copied to clipboard
val isProLicensed: StatusSignal<Boolean?>?
Link copied to clipboard
val magnetHealth: StatusSignal<MagnetHealthValue?>?
Link copied to clipboard
val network: CANBus?
Link copied to clipboard
val offset: Rotation2d

Gets the current magnet offset.

Link copied to clipboard
val position: StatusSignal<Angle?>?
Link copied to clipboard
val positionSinceBoot: StatusSignal<Angle?>?
Link copied to clipboard

Gets the absolute position in radians (0.0 to 2π).

Link copied to clipboard
val rotation: Rotation2d

Gets the absolute position of the encoder as a Rotation2d.

Link copied to clipboard

Gets the absolute position in rotations (0.0 to 1.0).

Link copied to clipboard
val simState: CANcoderSimState?
Link copied to clipboard
val stickyFault_BadMagnet: StatusSignal<Boolean?>?
Link copied to clipboard
Link copied to clipboard
val stickyFault_Hardware: StatusSignal<Boolean?>?
Link copied to clipboard
val stickyFault_Undervoltage: StatusSignal<Boolean?>?
Link copied to clipboard
Link copied to clipboard
val stickyFaultField: StatusSignal<Int?>?
Link copied to clipboard
val supplyVoltage: StatusSignal<Voltage?>?
Link copied to clipboard
val unfilteredVelocity: StatusSignal<AngularVelocity?>?
Link copied to clipboard
val velocity: StatusSignal<AngularVelocity?>?
Link copied to clipboard

Gets the velocity in degrees per second.

Link copied to clipboard

Gets the velocity in radians per second.

Link copied to clipboard

Gets the velocity in rotations per second.

Link copied to clipboard
val version: StatusSignal<Int?>?
Link copied to clipboard
val versionBugfix: StatusSignal<Int?>?
Link copied to clipboard
val versionBuild: StatusSignal<Int?>?
Link copied to clipboard
val versionMajor: StatusSignal<Int?>?
Link copied to clipboard
val versionMinor: StatusSignal<Int?>?

Functions

Link copied to clipboard

Sets the magnet offset to the current position.

Link copied to clipboard
fun clearStickyFault_BadMagnet(): StatusCode?
fun clearStickyFault_BadMagnet(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun clearStickyFault_BootDuringEnable(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun clearStickyFault_Hardware(): StatusCode?
fun clearStickyFault_Hardware(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun clearStickyFault_Undervoltage(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
Link copied to clipboard
fun clearStickyFaults(): StatusCode?
fun clearStickyFaults(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
open fun close()
Link copied to clipboard
fun configure(block: CANcoderConfiguration.() -> Unit = {})

Configures the CANcoder using a DSL-style configuration block.

Link copied to clipboard
fun configureSwerve(offset: Rotation2d = Rotation2d(), clockwisePositive: Boolean = false)

Configures the encoder for swerve module use with common settings.

Link copied to clipboard

Extension to configure an existing Engu for swerve use with a DSL.

Link copied to clipboard
fun Engu.getAngleError(target: Rotation2d): Rotation2d

Extension to get the angle error between current position and target.

Link copied to clipboard
Link copied to clipboard
open fun initSendable(builder: SendableBuilder?)
Link copied to clipboard
fun Engu.isAtAngle(target: Rotation2d, tolerance: Angle = Units.Degrees.of(2.0)): Boolean

Extension to check if encoder is within tolerance of target angle.

Link copied to clipboard
fun optimizeBusUtilization(): StatusCode?
fun optimizeBusUtilization(optimizedFreq: Frequency?): StatusCode?
fun optimizeBusUtilization(optimizedFreqHz: Double): StatusCode?
fun optimizeBusUtilization(optimizedFreq: Frequency?, timeoutSeconds: Double): StatusCode?
fun optimizeBusUtilization(optimizedFreqHz: Double, timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun resetSignalFrequencies(): StatusCode?
fun resetSignalFrequencies(timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun setControl(request: ControlRequest?): StatusCode?
Link copied to clipboard
fun setOffset(offset: Rotation2d)

Sets a specific offset in various units.

Link copied to clipboard
fun setOffsetDegrees(degrees: Double)

Sets a specific offset in degrees.

Link copied to clipboard
fun setOffsetRotations(rotations: Double)

Sets a specific offset in rotations.

Link copied to clipboard
fun setPosition(newValue: Angle?): StatusCode?
fun setPosition(newValue: Double): StatusCode?
fun setPosition(newValue: Angle?, timeoutSeconds: Double): StatusCode?
fun setPosition(newValue: Double, timeoutSeconds: Double): StatusCode?
Link copied to clipboard
fun Engu.shortestDistanceTo(target: Rotation2d): Double

Extension to get the shortest angular distance to target.

Link copied to clipboard

Extension to log encoder information to a string.