Class SmartMotorController

java.lang.Object
yams.motorcontrollers.SmartMotorController
Direct Known Subclasses:
NovaWrapper, SparkWrapper, TalonFXSWrapper, TalonFXWrapper

public abstract class SmartMotorController extends Object
Smart motor controller wrapper for motor controllers.
  • Field Details

  • Constructor Details

    • SmartMotorController

      public SmartMotorController()
  • Method Details

    • create

      public static SmartMotorController create(Object motorController, DCMotor motorSim, SmartMotorControllerConfig cfg)
      Create a SmartMotorController wrapper from the provided motor controller object.
      Parameters:
      motorController - Motor controller object.
      motorSim - DCMotor which the motor controller is connected too.
      cfg - SmartMotorControllerConfig for the SmartMotorController
      Returns:
      SmartMotorController.
    • isMotor

      public boolean isMotor(DCMotor a, DCMotor b)
      Compare DCMotors to identify the given motor.
      Parameters:
      a - DCMotor a
      b - DCMotor b
      Returns:
      True if same DC motor.
    • checkConfigSafety

      public void checkConfigSafety()
      Check config for safe values.
    • getSimSupplier

      public Optional<SimSupplier> getSimSupplier()
      Get the sim supplier.
      Returns:
      Sim supplier.
    • setSimSupplier

      public void setSimSupplier(SimSupplier mechanismSupplier)
      Set the SimSupplier Mechanism.
      Parameters:
      mechanismSupplier - Mechanism sim supplier.
    • stopClosedLoopController

      public void stopClosedLoopController()
      Stop the closed loop controller.
    • startClosedLoopController

      public void startClosedLoopController()
      Start the closed loop controller with the period.
    • iterateClosedLoopController

      public void iterateClosedLoopController()
      Iterate the closed loop controller. Feedforward are only applied with profiled pid controllers.
    • setupSimulation

      public abstract void setupSimulation()
      Setup the simulation for the wrapper.
    • seedRelativeEncoder

      public abstract void seedRelativeEncoder()
      Seed the relative encoder with the position from the absolute encoder.
    • synchronizeRelativeEncoder

      public abstract void synchronizeRelativeEncoder()
      Check if the relative encoder is out of sync with absolute encoder within defined tolerances.
    • simIterate

      public abstract void simIterate()
      Simulation iteration.
    • setIdleMode

      public abstract void setIdleMode(SmartMotorControllerConfig.MotorMode mode)
      Set the motor idle mode from COAST or BRAKE.
      Parameters:
      mode - SmartMotorControllerConfig.MotorMode selected.
    • setEncoderVelocity

      public abstract void setEncoderVelocity(AngularVelocity velocity)
      Set the encoder velocity
      Parameters:
      velocity - AngularVelocity of the Mechanism.
    • setEncoderVelocity

      public abstract void setEncoderVelocity(LinearVelocity velocity)
      Set the encoder velocity.
      Parameters:
      velocity - Measurement LinearVelocity
    • setEncoderPosition

      public abstract void setEncoderPosition(Angle angle)
      Set the encoder position
      Parameters:
      angle - Mechanism Angle to reach.
    • setEncoderPosition

      public abstract void setEncoderPosition(Distance distance)
      Set the encoder position.
      Parameters:
      distance - Measurement Distance to reach.
    • setPosition

      public abstract void setPosition(Angle angle)
      Set the Mechanism Angle using the PID and feedforward from SmartMotorControllerConfig.
      Parameters:
      angle - Mechanism angle to set.
    • setPosition

      public abstract void setPosition(Distance distance)
      Set the Mechanism Distance using the PID and feedforward from SmartMotorControllerConfig.
      Parameters:
      distance - Mechanism Distance to set.
    • setVelocity

      public abstract void setVelocity(LinearVelocity velocity)
      Set the Mechanism LinearVelocity using the PID and feedforward from SmartMotorControllerConfig.
      Parameters:
      velocity - Mechanism LinearVelocity to target.
    • setVelocity

      public abstract void setVelocity(AngularVelocity angle)
      Set the Mechanism AngularVelocity using the PID and feedforward from SmartMotorControllerConfig.
      Parameters:
      angle - Mechanism AngularVelocity to target.
    • getSysIdConfig

      protected SysIdRoutine.Config getSysIdConfig(Voltage maxVoltage, Velocity<VoltageUnit> stepVoltage, Time testDuration)
      Get the SysIdConfig which may need to have modifications based on the SmartMotorController, like TalonFX and TalonFXS to record states correctly.
      Parameters:
      maxVoltage - Maximum voltage of the SysIdRoutine.
      stepVoltage - Step voltage for the dynamic test in SysIdRoutine.
      testDuration - Duration of each SysIdRoutine run.
      Returns:
      SysIdRoutine.Config of the SysIdRoutine to run.
    • sysId

      public SysIdRoutine sysId(Voltage maxVoltage, Velocity<VoltageUnit> stepVoltage, Time testDuration)
      Run the SysIdRoutine which runs to the maximum MEASUREMENT at the step voltage then down to the minimum MEASUREMENT with the step voltage then up to the maximum MEASUREMENT increasing each second by the step voltage generated via the SmartMotorControllerConfig.
      Parameters:
      maxVoltage - Maximum voltage of the SysIdRoutine.
      stepVoltage - Step voltage for the dynamic test in SysIdRoutine.
      testDuration - Duration of each SysIdRoutine run.
      Returns:
      Sequential command group of SysIdRoutine running all required tests to the configured MINIMUM and MAXIMUM MEASUREMENTS.
    • applyConfig

      public abstract boolean applyConfig(SmartMotorControllerConfig config)
      Parameters:
      config - SmartMotorControllerConfig to use.
      Returns:
      Successful Application of the configuration.
    • getDutyCycle

      public abstract double getDutyCycle()
      Get the duty cycle output of the motor controller.
      Returns:
      DutyCyle of the motor controller.
    • setDutyCycle

      public abstract void setDutyCycle(double dutyCycle)
      Set the dutycycle output of the motor controller.
      Parameters:
      dutyCycle - Value between [-1,1]
    • getSupplyCurrent

      public abstract Optional<Current> getSupplyCurrent()
      Get the supply current of the motor controller.
      Returns:
      The supply current of the motor controller.
    • getStatorCurrent

      public abstract Current getStatorCurrent()
      Get the stator current of the motor controller.
      Returns:
      Stator current
    • getVoltage

      public abstract Voltage getVoltage()
      Get the voltage output of the motor.
      Returns:
      Voltage output of the motor.
    • setVoltage

      public abstract void setVoltage(Voltage voltage)
      Set the voltage output of the motor controller. Useful for Sysid.
      Parameters:
      voltage - Voltage to set the motor controller output to.
    • getDCMotor

      public abstract DCMotor getDCMotor()
      Get the DCMotor modeling the motor controlled by the motor controller.
      Returns:
      DCMotor of the controlled motor.
    • getMeasurementVelocity

      public abstract LinearVelocity getMeasurementVelocity()
      Get the usable measurement of the motor for mechanisms operating under distance units converted with the SmartMotorControllerConfig.
      Returns:
      Measurement velocity of the mechanism post-gearing.
    • getMeasurementPosition

      public abstract Distance getMeasurementPosition()
      Get the usable measurement of the motor for mechanisms operating under distance units converted with the SmartMotorControllerConfig.
      Returns:
      Measurement velocity of the mechanism post-gearing.
    • getMechanismVelocity

      public abstract AngularVelocity getMechanismVelocity()
      Get the Mechanism AngularVelocity taking the configured MechanismGearing into the measurement applied via the SmartMotorControllerConfig.
      Returns:
      Mechanism AngularVelocity
    • getMechanismPosition

      public abstract Angle getMechanismPosition()
      Get the mechanism Angle taking the configured MechanismGearing from SmartMotorControllerConfig.
      Returns:
      Mechanism Angle
    • getRotorVelocity

      public abstract AngularVelocity getRotorVelocity()
      Gets the angular velocity of the motor.
      Returns:
      AngularVelocity of the relative motor encoder.
    • getRotorPosition

      public abstract Angle getRotorPosition()
      Get the rotations of the motor with the relative encoder since the motor controller powered on scaled to the mechanism rotations.
      Returns:
      Angle of the relative encoder in the motor.
    • setupTelemetry

      public void setupTelemetry(NetworkTable telemetry, NetworkTable tuning)
      Update the telemetry under the motor name under the given NetworkTable
      Parameters:
      telemetry - NetworkTable to create the SmartMotorControllerTelemetry subtable under based off of SmartMotorControllerConfig.getTelemetryName().
      tuning - NetworkTable to create the tunable telemetry from SmartMotorControllerTelemetry subtable under. Based off of SmartMotorControllerConfig.getTelemetryName().
    • setupTelemetry

      public void setupTelemetry()
      Setup Telemetry with default NT path
    • updateTelemetry

      public void updateTelemetry()
      Update the telemetry under the motor name under the given NetworkTable
    • setMotorInverted

      public abstract void setMotorInverted(boolean inverted)
      Set the inversion state of the motor.
      Parameters:
      inverted - Inverted motor.
    • setEncoderInverted

      public abstract void setEncoderInverted(boolean inverted)
      Set the phase of the encoder attached to the brushless motor.
      Parameters:
      inverted - Phase of the encoder.
    • setMotionProfileMaxVelocity

      public abstract void setMotionProfileMaxVelocity(LinearVelocity maxVelocity)
      Set the maximum velocity of the trapezoidal profile for the feedback controller.
      Parameters:
      maxVelocity - Maximum velocity, will be translated to MetersPerSecond.
    • setMotionProfileMaxAcceleration

      public abstract void setMotionProfileMaxAcceleration(LinearAcceleration maxAcceleration)
      Set the maximum acceleration of the trapezoidal profile for the feedback controller.
      Parameters:
      maxAcceleration - Maximum acceleration, will be translated to MetersPerSecondPerSecond.
    • setMotionProfileMaxVelocity

      public abstract void setMotionProfileMaxVelocity(AngularVelocity maxVelocity)
      Set the maximum velocity for the trapezoidal profile for the feedback controller.
      Parameters:
      maxVelocity - Maximum velocity, will be translated to RotationsPerSecond.
    • setMotionProfileMaxAcceleration

      public abstract void setMotionProfileMaxAcceleration(AngularAcceleration maxAcceleration)
      Set the maximum acceleration for the trapezoidal profile for the feedback controller.
      Parameters:
      maxAcceleration - Maximum acceleration, will be translated to RotationsPerSecondPerSecond.
    • setKp

      public abstract void setKp(double kP)
      Set kP for the feedback controller PID.
      Parameters:
      kP - kP
    • setKi

      public abstract void setKi(double kI)
      Set kI for the feedback controller PID.
      Parameters:
      kI - kI.
    • setKd

      public abstract void setKd(double kD)
      Set kD for the feedback controller PID.
      Parameters:
      kD - kD for the feedback controller PID.
    • setFeedback

      public abstract void setFeedback(double kP, double kI, double kD)
      Set the closed loop feedback controller PID.
      Parameters:
      kP - kP; Proportional scalar.
      kI - kI; Integral scalar.
      kD - kD; derivative scalar.
    • setKs

      public abstract void setKs(double kS)
      Static feedforward element.
      Parameters:
      kS - kS; Static feedforward.
    • setKv

      public abstract void setKv(double kV)
      Velocity feedforward element.
      Parameters:
      kV - kV; Velocity feedforward.
    • setKa

      public abstract void setKa(double kA)
      Acceleration feedforward element.
      Parameters:
      kA - kA; Acceleration feedforward.
    • setKg

      public abstract void setKg(double kG)
      kSin feedforward element.
      Parameters:
      kG - kG; Gravity feedforward.
    • setFeedforward

      public abstract void setFeedforward(double kS, double kV, double kA, double kG)
      Set the feedforward controller.
      Parameters:
      kS - kS; Static feedforward.
      kV - kV; Velocity feedforward.
      kA - kA; Acceleration feedforward.
      kG - kG; Gravity feedforward.
    • setStatorCurrentLimit

      public abstract void setStatorCurrentLimit(Current currentLimit)
      Set the stator current limit for the device.
      Parameters:
      currentLimit - Stator current limit.
    • setSupplyCurrentLimit

      public abstract void setSupplyCurrentLimit(Current currentLimit)
      Set the supply current limit.
      Parameters:
      currentLimit - Supply current limit.
    • setClosedLoopRampRate

      public abstract void setClosedLoopRampRate(Time rampRate)
      Set the closed loop ramp rate. The ramp rate is how fast the motor can go from 0-100, measured in seconds.
      Parameters:
      rampRate - Time from 0 to 100.
    • setOpenLoopRampRate

      public abstract void setOpenLoopRampRate(Time rampRate)
      Set the open loop ramp rate. The ramp rate is how fast the motor can go from 0 to 100, measured in Seconds.
      Parameters:
      rampRate - Time it takes to go from 0 to 100.
    • setMeasurementUpperLimit

      public abstract void setMeasurementUpperLimit(Distance upperLimit)
      Set the measurement upper limit, only works if mechanism circumference is defined.
      Parameters:
      upperLimit - Upper limit, will be translated to meters.
    • setMeasurementLowerLimit

      public abstract void setMeasurementLowerLimit(Distance lowerLimit)
      Set the measurement lower limit, only works if mechanism circumference is defined.
      Parameters:
      lowerLimit - Lower limit, will be translated to meters.
    • setMechanismUpperLimit

      public abstract void setMechanismUpperLimit(Angle upperLimit)
      Set the mechanism upper limit.
      Parameters:
      upperLimit - Upper limit, will be translated to rotations.
    • setMechanismLowerLimit

      public abstract void setMechanismLowerLimit(Angle lowerLimit)
      Set the mechanism lower limit.
      Parameters:
      lowerLimit - Lower limit, will be translated to rotations.
    • getTemperature

      public abstract Temperature getTemperature()
      Get the SmartMotorController temperature.
      Returns:
      Temperature
    • getConfig

      public abstract SmartMotorControllerConfig getConfig()
      Returns:
      SmartMotorControllerConfig used.
    • getMotorController

      public abstract Object getMotorController()
      Get the Motor Controller Object passed into the SmartMotorController.
      Returns:
      Motor Controller object.
    • getMotorControllerConfig

      public abstract Object getMotorControllerConfig()
      Get the motor controller object config generated by SmartMotorController based off the SmartMotorControllerConfig
      Returns:
      Motor controller config.
    • getMechanismPositionSetpoint

      public Optional<Angle> getMechanismPositionSetpoint()
      Get the Mechanism setpoint position.
      Returns:
      Mechanism Setpoint position.
    • getMechanismSetpointVelocity

      public Optional<AngularVelocity> getMechanismSetpointVelocity()
      Get the Mechanism velocity setpoint.
      Returns:
      Mechanism velocity setpoint.
    • getUnsupportedTelemetryFields

      Get a list of unsupported telemetry fields if any exist.
      Returns:
      Optional list of unsupported telemetry fields.
    • getName

      public String getName()
      Get the name of the SmartMotorController
      Returns:
      String name if present, else "SmartMotorController"
    • close

      public void close()
      Close the SMC for unit testing.