Class AbstractMotor
- Direct Known Subclasses:
AbstractSimMotor,AbstractVelocityMotor,HarvesterMotor,TurretMotor
All positions are expressed in radians and velocities in radians per second to align with WPILib math utilities. If a subsystem or config prefers
degrees for readability, convert to radians at the call site (e.g., Units.degreesToRadians(...)).
-
Nested Class Summary
Nested classes/interfaces inherited from interface frc.robot.devices.motor.MotorIO
MotorIO.MotorIOInputs -
Field Summary
FieldsModifier and TypeFieldDescriptionprotected final LoggerShared logger instance used for warnings and verbose updates.protected final com.revrobotics.spark.SparkMaxHardware controller that actually drives the motor output.protected final StringFriendly name used in log messages and dashboard keys.protected static final doubleNominal voltage used for reference calculations. -
Constructor Summary
ConstructorsModifierConstructorDescriptionprotectedAbstractMotor(String name, MotorConfig config) Creates a motor wrapper backed by a shared motor config using the default brushless SparkMax type.protectedAbstractMotor(String name, MotorConfig config, com.revrobotics.spark.SparkLowLevel.MotorType motorType) Creates a motor wrapper backed by a shared motor config and explicit motor type. -
Method Summary
Modifier and TypeMethodDescriptionprotected static doublecomputeMechanismRadiansPerMotorRotation(double motorRotationsPerMechanismRotation) Converts a gear ratio in motor rotations per mechanism rotation into mechanism radians per motor rotation.protected abstract com.revrobotics.spark.config.SparkMaxConfigconfigureMotor(com.revrobotics.spark.config.SparkMaxConfig config) Allows subclasses to append motor-specific configuration before the object is applied to hardware.doubleReports the current measured position in radians.doubleReports the current measured velocity in radians per second.edu.wpi.first.units.measure.VoltageReports the applied voltage.final voidinit()Applies hardware configuration after the subclass has finished assigning its config.final booleanReports whether the motor has been initialized with hardware configuration.voidsetEncoderPosition(double positionRadians) Overwrites the encoder's stored position so the mechanism's logical zero matches its physical location.voidsetVoltage(edu.wpi.first.units.measure.Voltage voltage) Commands the motor with a voltage request.voidstop()Stops motor output immediately.voidupdateInputs(MotorIO.MotorIOInputs inputs) Populates the inputs structure with the most recent readings from the motor controller.
-
Field Details
-
NOMINAL_VOLTAGE
protected static final double NOMINAL_VOLTAGENominal voltage used for reference calculations.Firmware-level voltage compensation is intentionally disabled on all motors because WPILib's
MotorController.setVoltage()already scales duty cycle by the measured battery voltage. Enabling both creates double compensation that causes systematic overshoot when the battery sags below 12 V.- See Also:
-
name
Friendly name used in log messages and dashboard keys. -
log
Shared logger instance used for warnings and verbose updates. -
motor
protected final com.revrobotics.spark.SparkMax motorHardware controller that actually drives the motor output.
-
-
Constructor Details
-
Method Details
-
computeMechanismRadiansPerMotorRotation
protected static double computeMechanismRadiansPerMotorRotation(double motorRotationsPerMechanismRotation) Converts a gear ratio in motor rotations per mechanism rotation into mechanism radians per motor rotation.- Parameters:
motorRotationsPerMechanismRotation- motor rotations per one mechanism rotation- Returns:
- mechanism radians per motor rotation (defaults to 1:1 when the ratio is invalid)
-
init
public final void init()Applies hardware configuration after the subclass has finished assigning its config.Call this once in the concrete motor constructor, after any config fields are assigned. Subsequent calls are ignored.
-
isInitialized
public final boolean isInitialized()Reports whether the motor has been initialized with hardware configuration.- Returns:
- true when
init()has completed successfully
-
setVoltage
public void setVoltage(edu.wpi.first.units.measure.Voltage voltage) Description copied from interface:MotorCommands the motor with a voltage request.Use this when closed-loop or feedforward logic has already computed the needed voltage. Implementations should apply the value immediately without additional scaling.
- Specified by:
setVoltagein interfaceMotor- Parameters:
voltage- desired output voltage, in volts
-
stop
public void stop()Stops motor output immediately. -
getPositionRadians
public double getPositionRadians()Reports the current measured position in radians.The raw encoder value is in motor rotations. This method multiplies by the stored conversion factor to return mechanism radians. The conversion is done in Java rather than relying on SparkMax firmware conversion factors for reliability across REVLib versions.
- Specified by:
getPositionRadiansin interfaceMotor- Returns:
- mechanism position (radians)
-
setEncoderPosition
public void setEncoderPosition(double positionRadians) Overwrites the encoder's stored position so the mechanism's logical zero matches its physical location.The caller provides the value in mechanism radians. This method converts back to motor rotations before writing to the encoder.
- Specified by:
setEncoderPositionin interfaceMotor- Parameters:
positionRadians- new encoder position in mechanism radians
-
getVelocityRadiansPerSecond
public double getVelocityRadiansPerSecond()Reports the current measured velocity in radians per second.The raw encoder value is in motor RPM. This method multiplies by the stored conversion factor to return mechanism radians per second. The conversion is done in Java rather than relying on SparkMax firmware conversion factors for reliability across REVLib versions.
- Specified by:
getVelocityRadiansPerSecondin interfaceMotor- Returns:
- mechanism velocity (radians/second)
-
getVoltage
public edu.wpi.first.units.measure.Voltage getVoltage()Description copied from interface:MotorReports the applied voltage.Use this for logging or validation that the controller output matches expectations.
- Specified by:
getVoltagein interfaceMotor- Returns:
- voltage applied to the motor, in volts
-
updateInputs
Description copied from interface:MotorIOPopulates the inputs structure with the most recent readings from the motor controller.- Specified by:
updateInputsin interfaceMotorIO- Parameters:
inputs- mutable inputs container to fill for logging
-
configureMotor
protected abstract com.revrobotics.spark.config.SparkMaxConfig configureMotor(com.revrobotics.spark.config.SparkMaxConfig config) Allows subclasses to append motor-specific configuration before the object is applied to hardware.- Parameters:
config- initialSparkMaxConfigwith default voltage compensation- Returns:
- configured
SparkMaxConfigready forSparkMax.configure(com.revrobotics.spark.config.SparkBaseConfig, com.revrobotics.spark.SparkBase.ResetMode, com.revrobotics.spark.SparkBase.PersistMode)
-