Class AbstractSimMotor

java.lang.Object
frc.robot.devices.motor.AbstractMotor
frc.robot.devices.motor.AbstractSimMotor
All Implemented Interfaces:
Motor, MotorIO
Direct Known Subclasses:
AbstractVelocitySimMotor, HarvesterSimMotor, TurretSimMotor

public abstract class AbstractSimMotor extends AbstractMotor
Abstract simulation-only motor wrapper that mirrors AbstractMotor behavior while using REV simulation helpers.

This class pairs a SparkMaxSim with a DCMotorSim so the simulated Spark MAX follows the same control modes, soft limits, and conversion factors as the real robot. Motion is modeled in radians and seconds to match the rest of the robot math.

  • Constructor Details

    • AbstractSimMotor

      protected AbstractSimMotor(String name, MotorConfig config, Supplier<Double> maximumVelocityDegreesPerSecondSupplier, Supplier<Double> maximumAccelerationDegreesPerSecondSqSupplier)
      Creates a simulated motor using the default NEO motor model.

      Use this when your mechanism is driven by a single NEO motor and you want the simulated Spark MAX to follow the same configuration and limits as the real robot.

      Parameters:
      name - friendly name used for logging
      config - motor configuration bundle for limits, gear ratio, and inversion
      maximumVelocityDegreesPerSecondSupplier - supplier yielding the max mechanism velocity (degrees per second)
      maximumAccelerationDegreesPerSecondSqSupplier - supplier yielding the max mechanism acceleration (degrees per second squared)
    • AbstractSimMotor

      protected AbstractSimMotor(String name, MotorConfig config, Supplier<Double> maximumVelocityDegreesPerSecondSupplier, Supplier<Double> maximumAccelerationDegreesPerSecondSqSupplier, edu.wpi.first.math.system.plant.DCMotor motorModel)
      Creates a simulated motor using an explicit motor model for improved realism.

      Use this when you know the exact motor type (for example, NEO 550) or the number of motors in the gearbox.

      Parameters:
      name - friendly name used for logging
      config - motor configuration bundle for limits, gear ratio, and inversion
      maximumVelocityDegreesPerSecondSupplier - supplier yielding the max mechanism velocity (degrees per second)
      maximumAccelerationDegreesPerSecondSqSupplier - supplier yielding the max mechanism acceleration (degrees per second squared)
      motorModel - motor model (for example, DCMotor.getNEO(int))
  • Method Details

    • updateInputs

      public void updateInputs(MotorIO.MotorIOInputs inputs)
      Updates the physics model and then exports sensor values from the simulated Spark MAX.
      Specified by:
      updateInputs in interface MotorIO
      Overrides:
      updateInputs in class AbstractMotor
      Parameters:
      inputs - mutable inputs container to fill for logging
    • setEncoderPosition

      public void setEncoderPosition(double positionRadians)
      Overwrites the real encoder, the SparkMaxSim, and the physics model position.

      All three position stores must stay in sync. Without updating the DCMotorSim, the physics model starts from a stale position and soft-limit clamping prevents it from ever reaching the encoder's reported value; the motor appears frozen in telemetry.

      Specified by:
      setEncoderPosition in interface Motor
      Overrides:
      setEncoderPosition in class AbstractMotor
      Parameters:
      positionRadians - new encoder position in mechanism radians
    • configureMotor

      protected com.revrobotics.spark.config.SparkMaxConfig configureMotor(com.revrobotics.spark.config.SparkMaxConfig sparkConfig)
      Applies the base configuration for the simulated Spark MAX.

      This mirrors the inversion, current limits, and voltage compensation used on the real controller so the simulation follows the same control assumptions.

      Specified by:
      configureMotor in class AbstractMotor
      Parameters:
      sparkConfig - base SparkMax config to mutate
      Returns:
      updated SparkMax config ready for SparkMax.configure(com.revrobotics.spark.config.SparkBaseConfig, com.revrobotics.spark.SparkBase.ResetMode, com.revrobotics.spark.SparkBase.PersistMode)