Package yams.motorcontrollers
Class SmartMotorController
java.lang.Object
yams.motorcontrollers.SmartMotorController
- Direct Known Subclasses:
NovaWrapper,SparkWrapper,TalonFXSWrapper,TalonFXWrapper
Smart motor controller wrapper for motor controllers.
-
Field Summary
FieldsModifier and TypeFieldDescriptionprotected NotifierThread of the closed loop controller.protected SmartMotorControllerConfigSmartMotorControllerConfigfor the motor.protected Optional<ExponentialProfilePIDController>Exponential profile PID controller for the motor controller.protected Optional<SmartMotorController[]>Loosely coupled followers.protected Optional<ProfiledPIDController>Profiled PID controller for the motor controller.protected Optional<PIDController>Simple PID controller for the motor controller.protected Optional<SimSupplier>SimSupplierfor the mechanism.protected Optional<NetworkTable>Parent table for telemetry.Setpoint positionprotected Optional<AngularVelocity>Setpoint velocity.protected SmartMotorControllerTelemetryTelemetry.protected Optional<SmartMotorControllerTelemetryConfig>Config for publishing specific telemetry.protected Optional<NetworkTable>SmartMotorControllertelemetry table.protected Optional<NetworkTable>SmartMotorControllertuning table. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptionabstract booleanApply theSmartMotorControllerConfigto theSmartMotorController.voidCheck config for safe values.voidclose()Close the SMC for unit testing.static SmartMotorControllercreate(Object motorController, DCMotor motorSim, SmartMotorControllerConfig cfg) Create aSmartMotorControllerwrapper from the provided motor controller object.abstract SmartMotorControllerConfigGet theSmartMotorControllerConfigfor theSmartMotorControllerabstract DCMotorGet theDCMotormodeling the motor controlled by the motor controller.abstract doubleGet the duty cycle output of the motor controller.abstract DistanceGet the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.abstract LinearVelocityGet the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.abstract AngleGet the Mechanism setpoint position.Get the Mechanism velocity setpoint.abstract AngularVelocityGet the MechanismAngularVelocitytaking the configuredMechanismGearinginto the measurement applied via theSmartMotorControllerConfig.abstract ObjectGet the Motor Controller Object passed into theSmartMotorController.abstract ObjectGet the motor controller object config generated bySmartMotorControllerbased off theSmartMotorControllerConfiggetName()Get the name of theSmartMotorControllerabstract AngleGet the rotations of the motor with the relative encoder since the motor controller powered on scaled to the mechanism rotations.abstract AngularVelocityGets the angular velocity of the motor.Get the sim supplier.abstract CurrentGet the stator current of the motor controller.Get the supply current of the motor controller.protected SysIdRoutine.ConfiggetSysIdConfig(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.abstract TemperatureGet theSmartMotorControllertemperature.abstract Pair<Optional<List<SmartMotorControllerTelemetry.BooleanTelemetryField>>,Optional<List<SmartMotorControllerTelemetry.DoubleTelemetryField>>> Get a list of unsupported telemetry fields if any exist.abstract VoltageGet the voltage output of the motor.booleanCompareDCMotors to identify the given motor.voidIterate the closed loop controller.abstract voidSeed the relative encoder with the position from the absolute encoder.abstract voidsetClosedLoopRampRate(Time rampRate) Set the closed loop ramp rate.abstract voidsetDutyCycle(double dutyCycle) Set the dutycycle output of the motor controller.abstract voidsetEncoderInverted(boolean inverted) Set the phase of the encoder attached to the brushless motor.abstract voidsetEncoderPosition(Angle angle) Set the encoder positionabstract voidsetEncoderPosition(Distance distance) Set the encoder position.abstract voidsetEncoderVelocity(AngularVelocity velocity) Set the encoder velocityabstract voidsetEncoderVelocity(LinearVelocity velocity) Set the encoder velocity.abstract voidsetFeedback(double kP, double kI, double kD) Set the closed loop feedback controller PID.abstract voidsetFeedforward(double kS, double kV, double kA, double kG) Set the feedforward controller.abstract voidSet the motor idle mode from COAST or BRAKE.abstract voidsetKa(double kA) Acceleration feedforward element.abstract voidsetKd(double kD) Set kD for the feedback controller PID.abstract voidsetKg(double kG) kSin feedforward element.abstract voidsetKi(double kI) Set kI for the feedback controller PID.abstract voidsetKp(double kP) Set kP for the feedback controller PID.abstract voidsetKs(double kS) Static feedforward element.abstract voidsetKv(double kV) Velocity feedforward element.abstract voidsetMeasurementLowerLimit(Distance lowerLimit) Set the measurement lower limit, only works if mechanism circumference is defined.abstract voidsetMeasurementUpperLimit(Distance upperLimit) Set the measurement upper limit, only works if mechanism circumference is defined.abstract voidsetMechanismLowerLimit(Angle lowerLimit) Set the mechanism lower limit.abstract voidsetMechanismUpperLimit(Angle upperLimit) Set the mechanism upper limit.abstract voidsetMotionProfileMaxAcceleration(AngularAcceleration maxAcceleration) Set the maximum acceleration for the trapezoidal profile for the feedback controller.abstract voidsetMotionProfileMaxAcceleration(LinearAcceleration maxAcceleration) Set the maximum acceleration of the trapezoidal profile for the feedback controller.abstract voidsetMotionProfileMaxVelocity(AngularVelocity maxVelocity) Set the maximum velocity for the trapezoidal profile for the feedback controller.abstract voidsetMotionProfileMaxVelocity(LinearVelocity maxVelocity) Set the maximum velocity of the trapezoidal profile for the feedback controller.abstract voidsetMotorInverted(boolean inverted) Set the inversion state of the motor.abstract voidsetOpenLoopRampRate(Time rampRate) Set the open loop ramp rate.abstract voidsetPosition(Angle angle) Set the MechanismAngleusing the PID and feedforward fromSmartMotorControllerConfig.abstract voidsetPosition(Distance distance) Set the MechanismDistanceusing the PID and feedforward fromSmartMotorControllerConfig.voidsetSimSupplier(SimSupplier mechanismSupplier) Set theSimSupplierMechanism.abstract voidsetStatorCurrentLimit(Current currentLimit) Set the stator current limit for the device.abstract voidsetSupplyCurrentLimit(Current currentLimit) Set the supply current limit.abstract voidSetup the simulation for the wrapper.voidSetup Telemetry with default NT pathvoidsetupTelemetry(NetworkTable telemetry, NetworkTable tuning) Update the telemetry under the motor name under the givenNetworkTableabstract voidsetVelocity(AngularVelocity angle) Set the MechanismAngularVelocityusing the PID and feedforward fromSmartMotorControllerConfig.abstract voidsetVelocity(LinearVelocity velocity) Set the MechanismLinearVelocityusing the PID and feedforward fromSmartMotorControllerConfig.abstract voidsetVoltage(Voltage voltage) Set the voltage output of the motor controller.abstract voidSimulation iteration.voidStart the closed loop controller with the period.voidStop the closed loop controller.abstract voidCheck if the relative encoder is out of sync with absolute encoder within defined tolerances.sysId(Voltage maxVoltage, Velocity<VoltageUnit> stepVoltage, Time testDuration) Run theSysIdRoutinewhich 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 theSmartMotorControllerConfig.voidUpdate the telemetry under the motor name under the givenNetworkTable
-
Field Details
-
telemetry
Telemetry. -
m_config
SmartMotorControllerConfigfor the motor. -
m_pidController
Profiled PID controller for the motor controller. -
m_expoPidController
Exponential profile PID controller for the motor controller. -
m_simplePidController
Simple PID controller for the motor controller. -
setpointPosition
Setpoint position -
setpointVelocity
Setpoint velocity. -
m_closedLoopControllerThread
Thread of the closed loop controller. -
parentTable
Parent table for telemetry. -
telemetryTable
SmartMotorControllertelemetry table. -
tuningTable
SmartMotorControllertuning table. -
telemetryConfig
Config for publishing specific telemetry. -
m_simSupplier
SimSupplierfor the mechanism. -
m_looseFollowers
Loosely coupled followers.
-
-
Constructor Details
-
SmartMotorController
public SmartMotorController()
-
-
Method Details
-
create
public static SmartMotorController create(Object motorController, DCMotor motorSim, SmartMotorControllerConfig cfg) Create aSmartMotorControllerwrapper from the provided motor controller object.- Parameters:
motorController- Motor controller object.motorSim-DCMotorwhich the motor controller is connected too.cfg-SmartMotorControllerConfigfor theSmartMotorController- Returns:
SmartMotorController.
-
isMotor
CompareDCMotors to identify the given motor. -
checkConfigSafety
public void checkConfigSafety()Check config for safe values. -
getSimSupplier
Get the sim supplier.- Returns:
- Sim supplier.
-
setSimSupplier
Set theSimSupplierMechanism.- 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
Set the motor idle mode from COAST or BRAKE.- Parameters:
mode-SmartMotorControllerConfig.MotorModeselected.
-
setEncoderVelocity
Set the encoder velocity- Parameters:
velocity-AngularVelocityof the Mechanism.
-
setEncoderVelocity
Set the encoder velocity.- Parameters:
velocity- MeasurementLinearVelocity
-
setEncoderPosition
Set the encoder position- Parameters:
angle- MechanismAngleto reach.
-
setEncoderPosition
Set the encoder position.- Parameters:
distance- MeasurementDistanceto reach.
-
setPosition
Set the MechanismAngleusing the PID and feedforward fromSmartMotorControllerConfig.- Parameters:
angle- Mechanism angle to set.
-
setPosition
Set the MechanismDistanceusing the PID and feedforward fromSmartMotorControllerConfig.- Parameters:
distance- MechanismDistanceto set.
-
setVelocity
Set the MechanismLinearVelocityusing the PID and feedforward fromSmartMotorControllerConfig.- Parameters:
velocity- MechanismLinearVelocityto target.
-
setVelocity
Set the MechanismAngularVelocityusing the PID and feedforward fromSmartMotorControllerConfig.- Parameters:
angle- MechanismAngularVelocityto 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 theSysIdRoutine.stepVoltage- Step voltage for the dynamic test inSysIdRoutine.testDuration- Duration of eachSysIdRoutinerun.- Returns:
SysIdRoutine.Configof theSysIdRoutineto run.
-
sysId
Run theSysIdRoutinewhich 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 theSmartMotorControllerConfig.- Parameters:
maxVoltage- Maximum voltage of theSysIdRoutine.stepVoltage- Step voltage for the dynamic test inSysIdRoutine.testDuration- Duration of eachSysIdRoutinerun.- Returns:
- Sequential command group of
SysIdRoutinerunning all required tests to the configured MINIMUM and MAXIMUM MEASUREMENTS.
-
applyConfig
Apply theSmartMotorControllerConfigto theSmartMotorController.- Parameters:
config-SmartMotorControllerConfigto 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
Get the supply current of the motor controller.- Returns:
- The supply current of the motor controller.
-
getStatorCurrent
Get the stator current of the motor controller.- Returns:
- Stator current
-
getVoltage
Get the voltage output of the motor.- Returns:
- Voltage output of the motor.
-
setVoltage
Set the voltage output of the motor controller. Useful for Sysid.- Parameters:
voltage- Voltage to set the motor controller output to.
-
getDCMotor
Get theDCMotormodeling the motor controlled by the motor controller.- Returns:
DCMotorof the controlled motor.
-
getMeasurementVelocity
Get the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.- Returns:
- Measurement velocity of the mechanism post-gearing.
-
getMeasurementPosition
Get the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.- Returns:
- Measurement velocity of the mechanism post-gearing.
-
getMechanismVelocity
Get the MechanismAngularVelocitytaking the configuredMechanismGearinginto the measurement applied via theSmartMotorControllerConfig.- Returns:
- Mechanism
AngularVelocity
-
getMechanismPosition
- Returns:
- Mechanism
Angle
-
getRotorVelocity
Gets the angular velocity of the motor.- Returns:
AngularVelocityof the relative motor encoder.
-
getRotorPosition
Get the rotations of the motor with the relative encoder since the motor controller powered on scaled to the mechanism rotations.- Returns:
Angleof the relative encoder in the motor.
-
setupTelemetry
Update the telemetry under the motor name under the givenNetworkTable- Parameters:
telemetry-NetworkTableto create theSmartMotorControllerTelemetrysubtable under based off ofSmartMotorControllerConfig.getTelemetryName().tuning-NetworkTableto create the tunable telemetry fromSmartMotorControllerTelemetrysubtable under. Based off ofSmartMotorControllerConfig.getTelemetryName().
-
setupTelemetry
public void setupTelemetry()Setup Telemetry with default NT path -
updateTelemetry
public void updateTelemetry()Update the telemetry under the motor name under the givenNetworkTable -
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
Set the maximum velocity of the trapezoidal profile for the feedback controller.- Parameters:
maxVelocity- Maximum velocity, will be translated to MetersPerSecond.
-
setMotionProfileMaxAcceleration
Set the maximum acceleration of the trapezoidal profile for the feedback controller.- Parameters:
maxAcceleration- Maximum acceleration, will be translated to MetersPerSecondPerSecond.
-
setMotionProfileMaxVelocity
Set the maximum velocity for the trapezoidal profile for the feedback controller.- Parameters:
maxVelocity- Maximum velocity, will be translated to RotationsPerSecond.
-
setMotionProfileMaxAcceleration
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
Set the stator current limit for the device.- Parameters:
currentLimit- Stator current limit.
-
setSupplyCurrentLimit
Set the supply current limit.- Parameters:
currentLimit- Supply current limit.
-
setClosedLoopRampRate
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
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
Set the measurement upper limit, only works if mechanism circumference is defined.- Parameters:
upperLimit- Upper limit, will be translated to meters.
-
setMeasurementLowerLimit
Set the measurement lower limit, only works if mechanism circumference is defined.- Parameters:
lowerLimit- Lower limit, will be translated to meters.
-
setMechanismUpperLimit
Set the mechanism upper limit.- Parameters:
upperLimit- Upper limit, will be translated to rotations.
-
setMechanismLowerLimit
Set the mechanism lower limit.- Parameters:
lowerLimit- Lower limit, will be translated to rotations.
-
getTemperature
Get theSmartMotorControllertemperature.- Returns:
Temperature
-
getConfig
Get theSmartMotorControllerConfigfor theSmartMotorController- Returns:
SmartMotorControllerConfigused.
-
getMotorController
Get the Motor Controller Object passed into theSmartMotorController.- Returns:
- Motor Controller object.
-
getMotorControllerConfig
Get the motor controller object config generated bySmartMotorControllerbased off theSmartMotorControllerConfig- Returns:
- Motor controller config.
-
getMechanismPositionSetpoint
Get the Mechanism setpoint position.- Returns:
- Mechanism Setpoint position.
-
getMechanismSetpointVelocity
Get the Mechanism velocity setpoint.- Returns:
- Mechanism velocity setpoint.
-
getUnsupportedTelemetryFields
public abstract Pair<Optional<List<SmartMotorControllerTelemetry.BooleanTelemetryField>>,Optional<List<SmartMotorControllerTelemetry.DoubleTelemetryField>>> getUnsupportedTelemetryFields()Get a list of unsupported telemetry fields if any exist.- Returns:
- Optional list of unsupported telemetry fields.
-
getName
Get the name of theSmartMotorController- Returns:
Stringname if present, else "SmartMotorController"
-
close
public void close()Close the SMC for unit testing.
-