Class SysIdHelper

java.lang.Object
frc.robot.shared.subsystems.SysIdHelper

public final class SysIdHelper extends Object
Factory for building SysId routines with consistent logging and unit handling.

Subsystems call createSimpleRoutine to obtain a ready-to-run SysIdRoutine that drives a single motor and records voltage, position, and velocity to AdvantageKit. Position and velocity suppliers must provide values in radians and radians per second respectively (mechanism-side, after gear ratio conversion).

WPILib's SysIdRoutineLog.MotorLog.angularVelocity() internally divides by 2pi (converting radians/sec to rotations/sec) before writing to the log file. To compensate, this helper pre-multiplies position and velocity by 2pi before logging so the division cancels out and the SysId analysis tool sees true radian-based values. This means the gains reported by the SysId tool can be used directly in the subsystem config with no manual correction needed. See the SysId tuning guide at src/main/java/frc/robot/shared/subsystems/SYSID_GUIDE.md for the full workflow.

  • Method Details

    • createSimpleRoutine

      public static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine createSimpleRoutine(AbstractSubsystem<?> subsystem, String motorLabel, Consumer<edu.wpi.first.units.measure.Voltage> applyVoltage, Supplier<edu.wpi.first.units.measure.Voltage> measuredVoltageSupplier, Runnable updateInputs, DoubleSupplier positionRadiansSupplier, DoubleSupplier velocityRadiansPerSecondSupplier, double rampRateVoltsPerSecond, double stepVoltage)
      Creates a SysId routine that commands a motor with raw voltage and logs the measured state.
      Parameters:
      subsystem - subsystem that owns the motor; used for command requirements
      motorLabel - name to attach to the motor in the SysId log (e.g., "Turret/motor")
      applyVoltage - consumer that forwards a voltage request to the motor controller
      measuredVoltageSupplier - supplier that reports the currently applied voltage in units.Volts
      updateInputs - runnable that refreshes sensor data before each SysId log sample
      positionRadiansSupplier - supplier of the mechanism position in radians (angular mechanisms)
      velocityRadiansPerSecondSupplier - supplier of the mechanism velocity in radians per second (angular mechanisms)
      rampRateVoltsPerSecond - quasistatic voltage ramp rate in volts per second
      stepVoltage - step voltage applied during dynamic tests in volts
      Returns:
      configured SysIdRoutine ready to emit dynamic and quasistatic commands
    • createSimpleRoutine

      public static edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine createSimpleRoutine(AbstractSubsystem<?> subsystem, String motorLabel, Consumer<edu.wpi.first.units.measure.Voltage> applyVoltage, Supplier<edu.wpi.first.units.measure.Voltage> measuredVoltageSupplier, Runnable updateInputs, DoubleSupplier positionRadiansSupplier, DoubleSupplier velocityRadiansPerSecondSupplier, DoubleSupplier rawMotorRpmSupplier, double rampRateVoltsPerSecond, double stepVoltage)
      Creates a SysId routine that commands a motor with raw voltage, logs the measured state, and records diagnostic telemetry including raw motor RPM.

      Position and velocity are pre-multiplied by 2pi before logging to cancel WPILib's internal รท2pi conversion. The gains reported by the SysId analysis tool can be used directly without correction.

      Parameters:
      subsystem - subsystem that owns the motor; used for command requirements
      motorLabel - name to attach to the motor in the SysId log (e.g., "Turret/motor")
      applyVoltage - consumer that forwards a voltage request to the motor controller
      measuredVoltageSupplier - supplier that reports the currently applied voltage in units.Volts
      updateInputs - runnable that refreshes sensor data before each SysId log sample
      positionRadiansSupplier - supplier of the mechanism position in radians (angular mechanisms)
      velocityRadiansPerSecondSupplier - supplier of the mechanism velocity in radians per second (angular mechanisms)
      rawMotorRpmSupplier - supplier of the raw encoder velocity in motor RPM for diagnostic logging
      rampRateVoltsPerSecond - quasistatic voltage ramp rate in volts per second
      stepVoltage - step voltage applied during dynamic tests in volts
      Returns:
      configured SysIdRoutine ready to emit dynamic and quasistatic commands