Package yams.motorcontrollers.remote
Class TalonFXWrapper
java.lang.Object
yams.motorcontrollers.SmartMotorController
yams.motorcontrollers.remote.TalonFXWrapper
TalonFX wrapper for a CTRE TalonFX motor controller.
-
Field Summary
Fields inherited from class yams.motorcontrollers.SmartMotorController
m_closedLoopControllerThread, m_config, m_expoPidController, m_looseFollowers, m_pidController, m_simplePidController, m_simSupplier, parentTable, setpointPosition, setpointVelocity, telemetry, telemetryConfig, telemetryTable, tuningTable -
Constructor Summary
ConstructorsConstructorDescriptionTalonFXWrapper(TalonFX controller, DCMotor motor, SmartMotorControllerConfig smartConfig) Create theTalonFXwrapper -
Method Summary
Modifier and TypeMethodDescriptionbooleanApply theSmartMotorControllerConfigto theSmartMotorController.Ensure setting is applied, retries every 10ms.Get theSmartMotorControllerConfigfor theSmartMotorControllerGet theDCMotormodeling the motor controlled by the motor controller.doubleGet the duty cycle output of the motor controller.Get the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.Get the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.Get the MechanismAngularVelocitytaking the configuredMechanismGearinginto the measurement applied via theSmartMotorControllerConfig.Get the Motor Controller Object passed into theSmartMotorController.Get the motor controller object config generated bySmartMotorControllerbased off theSmartMotorControllerConfigGet the rotations of the motor with the relative encoder since the motor controller powered on scaled to the mechanism rotations.Gets the angular velocity of the motor.Get 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.Get theSmartMotorControllertemperature.Pair<Optional<List<SmartMotorControllerTelemetry.BooleanTelemetryField>>,Optional<List<SmartMotorControllerTelemetry.DoubleTelemetryField>>> Get a list of unsupported telemetry fields if any exist.Get the voltage output of the motor.voidSeed the relative encoder with the position from the absolute encoder.voidsetClosedLoopRampRate(Time rampRate) Set the closed loop ramp rate.voidsetDutyCycle(double dutyCycle) Set the dutycycle output of the motor controller.voidsetEncoderInverted(boolean inverted) Set the phase of the encoder attached to the brushless motor.voidsetEncoderPosition(Angle angle) Set the encoder positionvoidsetEncoderPosition(Distance distance) Set the encoder position.voidsetEncoderVelocity(AngularVelocity velocity) Deprecated.voidsetEncoderVelocity(LinearVelocity velocity) Set the encoder velocity.voidsetFeedback(double kP, double kI, double kD) Set the closed loop feedback controller PID.voidsetFeedforward(double kS, double kV, double kA, double kG) Set the feedforward controller.voidSet the motor idle mode from COAST or BRAKE.voidsetKa(double kA) Acceleration feedforward element.voidsetKd(double kD) Set kD for the feedback controller PID.voidsetKg(double kG) kSin feedforward element.voidsetKi(double kI) Set kI for the feedback controller PID.voidsetKp(double kP) Set kP for the feedback controller PID.voidsetKs(double kS) Static feedforward element.voidsetKv(double kV) Velocity feedforward element.voidsetMeasurementLowerLimit(Distance lowerLimit) Set the measurement lower limit, only works if mechanism circumference is defined.voidsetMeasurementUpperLimit(Distance upperLimit) Set the measurement upper limit, only works if mechanism circumference is defined.voidsetMechanismLowerLimit(Angle lowerLimit) Set the mechanism lower limit.voidsetMechanismUpperLimit(Angle upperLimit) Set the mechanism upper limit.voidsetMotionProfileMaxAcceleration(AngularAcceleration maxAcceleration) Set the maximum acceleration for the trapezoidal profile for the feedback controller.voidsetMotionProfileMaxAcceleration(LinearAcceleration maxAcceleration) Set the maximum acceleration of the trapezoidal profile for the feedback controller.voidsetMotionProfileMaxVelocity(AngularVelocity maxVelocity) Set the maximum velocity for the trapezoidal profile for the feedback controller.voidsetMotionProfileMaxVelocity(LinearVelocity maxVelocity) Set the maximum velocity of the trapezoidal profile for the feedback controller.voidsetMotorInverted(boolean inverted) Set the inversion state of the motor.voidsetOpenLoopRampRate(Time rampRate) Set the open loop ramp rate.voidsetPosition(Angle angle) Set the MechanismAngleusing the PID and feedforward fromSmartMotorControllerConfig.voidsetPosition(Distance distance) Set the MechanismDistanceusing the PID and feedforward fromSmartMotorControllerConfig.voidsetStatorCurrentLimit(Current currentLimit) Set the stator current limit for the device.voidsetSupplyCurrentLimit(Current currentLimit) Deprecated.voidSetup the simulation for the wrapper.voidsetVelocity(AngularVelocity angularVelocity) Set the MechanismAngularVelocityusing the PID and feedforward fromSmartMotorControllerConfig.voidsetVelocity(LinearVelocity velocity) Set the MechanismLinearVelocityusing the PID and feedforward fromSmartMotorControllerConfig.voidsetVoltage(Voltage voltage) Set the voltage output of the motor controller.voidSimulation iteration.voidDeprecated.booleanCheck ifCANdiPWM1 is used as theExternalFeedbackConfigs.ExternalFeedbackSensorSourceinTalonFXConfiguration.Feedback.booleanCheck ifCANdiPWM1 is used as theExternalFeedbackConfigs.ExternalFeedbackSensorSourceinTalonFXConfiguration.Feedback.Methods inherited from class yams.motorcontrollers.SmartMotorController
checkConfigSafety, close, create, getMechanismPositionSetpoint, getMechanismSetpointVelocity, getName, getSimSupplier, isMotor, iterateClosedLoopController, setSimSupplier, setupTelemetry, setupTelemetry, startClosedLoopController, stopClosedLoopController, sysId, updateTelemetry
-
Constructor Details
-
TalonFXWrapper
Create theTalonFXwrapper- Parameters:
controller-TalonFXmotor-DCMotorsmartConfig-SmartMotorControllerConfig
-
-
Method Details
-
setupSimulation
public void setupSimulation()Description copied from class:SmartMotorControllerSetup the simulation for the wrapper.- Specified by:
setupSimulationin classSmartMotorController
-
seedRelativeEncoder
public void seedRelativeEncoder()Description copied from class:SmartMotorControllerSeed the relative encoder with the position from the absolute encoder.- Specified by:
seedRelativeEncoderin classSmartMotorController
-
synchronizeRelativeEncoder
Deprecated.Description copied from class:SmartMotorControllerCheck if the relative encoder is out of sync with absolute encoder within defined tolerances.- Specified by:
synchronizeRelativeEncoderin classSmartMotorController
-
simIterate
public void simIterate()Description copied from class:SmartMotorControllerSimulation iteration.- Specified by:
simIteratein classSmartMotorController
-
setIdleMode
Description copied from class:SmartMotorControllerSet the motor idle mode from COAST or BRAKE.- Specified by:
setIdleModein classSmartMotorController- Parameters:
mode-SmartMotorControllerConfig.MotorModeselected.
-
useCANdiPWM1
public boolean useCANdiPWM1()Check ifCANdiPWM1 is used as theExternalFeedbackConfigs.ExternalFeedbackSensorSourceinTalonFXConfiguration.Feedback.- Returns:
- True if CANdi PWM1 is used and configured.
-
useCANdiPWM2
public boolean useCANdiPWM2()Check ifCANdiPWM1 is used as theExternalFeedbackConfigs.ExternalFeedbackSensorSourceinTalonFXConfiguration.Feedback.- Returns:
- True if CANdi is used.
-
setEncoderVelocity
Deprecated.Description copied from class:SmartMotorControllerSet the encoder velocity- Specified by:
setEncoderVelocityin classSmartMotorController- Parameters:
velocity-AngularVelocityof the Mechanism.
-
setEncoderVelocity
Description copied from class:SmartMotorControllerSet the encoder velocity.- Specified by:
setEncoderVelocityin classSmartMotorController- Parameters:
velocity- MeasurementLinearVelocity
-
setEncoderPosition
Description copied from class:SmartMotorControllerSet the encoder position- Specified by:
setEncoderPositionin classSmartMotorController- Parameters:
angle- MechanismAngleto reach.
-
setEncoderPosition
Description copied from class:SmartMotorControllerSet the encoder position.- Specified by:
setEncoderPositionin classSmartMotorController- Parameters:
distance- MeasurementDistanceto reach.
-
setPosition
Description copied from class:SmartMotorControllerSet the MechanismAngleusing the PID and feedforward fromSmartMotorControllerConfig.- Specified by:
setPositionin classSmartMotorController- Parameters:
angle- Mechanism angle to set.
-
setPosition
Description copied from class:SmartMotorControllerSet the MechanismDistanceusing the PID and feedforward fromSmartMotorControllerConfig.- Specified by:
setPositionin classSmartMotorController- Parameters:
distance- MechanismDistanceto set.
-
setVelocity
Description copied from class:SmartMotorControllerSet the MechanismLinearVelocityusing the PID and feedforward fromSmartMotorControllerConfig.- Specified by:
setVelocityin classSmartMotorController- Parameters:
velocity- MechanismLinearVelocityto target.
-
setVelocity
Description copied from class:SmartMotorControllerSet the MechanismAngularVelocityusing the PID and feedforward fromSmartMotorControllerConfig.- Specified by:
setVelocityin classSmartMotorController- Parameters:
angularVelocity- MechanismAngularVelocityto target.
-
getDutyCycle
public double getDutyCycle()Description copied from class:SmartMotorControllerGet the duty cycle output of the motor controller.- Specified by:
getDutyCyclein classSmartMotorController- Returns:
- DutyCyle of the motor controller.
-
setDutyCycle
public void setDutyCycle(double dutyCycle) Description copied from class:SmartMotorControllerSet the dutycycle output of the motor controller.- Specified by:
setDutyCyclein classSmartMotorController- Parameters:
dutyCycle- Value between [-1,1]
-
applyConfig
Description copied from class:SmartMotorControllerApply theSmartMotorControllerConfigto theSmartMotorController.- Specified by:
applyConfigin classSmartMotorController- Parameters:
config-SmartMotorControllerConfigto use.- Returns:
- Successful Application of the configuration.
-
getSupplyCurrent
Description copied from class:SmartMotorControllerGet the supply current of the motor controller.- Specified by:
getSupplyCurrentin classSmartMotorController- Returns:
- The supply current of the motor controller.
-
getStatorCurrent
Description copied from class:SmartMotorControllerGet the stator current of the motor controller.- Specified by:
getStatorCurrentin classSmartMotorController- Returns:
- Stator current
-
getVoltage
Description copied from class:SmartMotorControllerGet the voltage output of the motor.- Specified by:
getVoltagein classSmartMotorController- Returns:
- Voltage output of the motor.
-
setVoltage
Description copied from class:SmartMotorControllerSet the voltage output of the motor controller. Useful for Sysid.- Specified by:
setVoltagein classSmartMotorController- Parameters:
voltage- Voltage to set the motor controller output to.
-
getDCMotor
Description copied from class:SmartMotorControllerGet theDCMotormodeling the motor controlled by the motor controller.- Specified by:
getDCMotorin classSmartMotorController- Returns:
DCMotorof the controlled motor.
-
getMeasurementVelocity
Description copied from class:SmartMotorControllerGet the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.- Specified by:
getMeasurementVelocityin classSmartMotorController- Returns:
- Measurement velocity of the mechanism post-gearing.
-
getMeasurementPosition
Description copied from class:SmartMotorControllerGet the usable measurement of the motor for mechanisms operating under distance units converted with theSmartMotorControllerConfig.- Specified by:
getMeasurementPositionin classSmartMotorController- Returns:
- Measurement velocity of the mechanism post-gearing.
-
getMechanismVelocity
Description copied from class:SmartMotorControllerGet the MechanismAngularVelocitytaking the configuredMechanismGearinginto the measurement applied via theSmartMotorControllerConfig.- Specified by:
getMechanismVelocityin classSmartMotorController- Returns:
- Mechanism
AngularVelocity
-
getMechanismPosition
Description copied from class:SmartMotorController- Specified by:
getMechanismPositionin classSmartMotorController- Returns:
- Mechanism
Angle
-
getRotorVelocity
Description copied from class:SmartMotorControllerGets the angular velocity of the motor.- Specified by:
getRotorVelocityin classSmartMotorController- Returns:
AngularVelocityof the relative motor encoder.
-
getRotorPosition
Description copied from class:SmartMotorControllerGet the rotations of the motor with the relative encoder since the motor controller powered on scaled to the mechanism rotations.- Specified by:
getRotorPositionin classSmartMotorController- Returns:
Angleof the relative encoder in the motor.
-
setMotorInverted
public void setMotorInverted(boolean inverted) Description copied from class:SmartMotorControllerSet the inversion state of the motor.- Specified by:
setMotorInvertedin classSmartMotorController- Parameters:
inverted- Inverted motor.
-
setEncoderInverted
public void setEncoderInverted(boolean inverted) Description copied from class:SmartMotorControllerSet the phase of the encoder attached to the brushless motor.- Specified by:
setEncoderInvertedin classSmartMotorController- Parameters:
inverted- Phase of the encoder.
-
setMotionProfileMaxVelocity
Description copied from class:SmartMotorControllerSet the maximum velocity of the trapezoidal profile for the feedback controller.- Specified by:
setMotionProfileMaxVelocityin classSmartMotorController- Parameters:
maxVelocity- Maximum velocity, will be translated to MetersPerSecond.
-
setMotionProfileMaxAcceleration
Description copied from class:SmartMotorControllerSet the maximum acceleration of the trapezoidal profile for the feedback controller.- Specified by:
setMotionProfileMaxAccelerationin classSmartMotorController- Parameters:
maxAcceleration- Maximum acceleration, will be translated to MetersPerSecondPerSecond.
-
setMotionProfileMaxVelocity
Description copied from class:SmartMotorControllerSet the maximum velocity for the trapezoidal profile for the feedback controller.- Specified by:
setMotionProfileMaxVelocityin classSmartMotorController- Parameters:
maxVelocity- Maximum velocity, will be translated to RotationsPerSecond.
-
setMotionProfileMaxAcceleration
Description copied from class:SmartMotorControllerSet the maximum acceleration for the trapezoidal profile for the feedback controller.- Specified by:
setMotionProfileMaxAccelerationin classSmartMotorController- Parameters:
maxAcceleration- Maximum acceleration, will be translated to RotationsPerSecondPerSecond.
-
forceConfigApply
Ensure setting is applied, retries every 10ms.- Returns:
StatusCodefrom the device.
-
setKp
public void setKp(double kP) Description copied from class:SmartMotorControllerSet kP for the feedback controller PID.- Specified by:
setKpin classSmartMotorController- Parameters:
kP- kP
-
setKi
public void setKi(double kI) Description copied from class:SmartMotorControllerSet kI for the feedback controller PID.- Specified by:
setKiin classSmartMotorController- Parameters:
kI- kI.
-
setKd
public void setKd(double kD) Description copied from class:SmartMotorControllerSet kD for the feedback controller PID.- Specified by:
setKdin classSmartMotorController- Parameters:
kD- kD for the feedback controller PID.
-
setFeedback
public void setFeedback(double kP, double kI, double kD) Description copied from class:SmartMotorControllerSet the closed loop feedback controller PID.- Specified by:
setFeedbackin classSmartMotorController- Parameters:
kP- kP; Proportional scalar.kI- kI; Integral scalar.kD- kD; derivative scalar.
-
setKs
public void setKs(double kS) Description copied from class:SmartMotorControllerStatic feedforward element.- Specified by:
setKsin classSmartMotorController- Parameters:
kS- kS; Static feedforward.
-
setKv
public void setKv(double kV) Description copied from class:SmartMotorControllerVelocity feedforward element.- Specified by:
setKvin classSmartMotorController- Parameters:
kV- kV; Velocity feedforward.
-
setKa
public void setKa(double kA) Description copied from class:SmartMotorControllerAcceleration feedforward element.- Specified by:
setKain classSmartMotorController- Parameters:
kA- kA; Acceleration feedforward.
-
setKg
public void setKg(double kG) Description copied from class:SmartMotorControllerkSin feedforward element.- Specified by:
setKgin classSmartMotorController- Parameters:
kG- kG; Gravity feedforward.
-
setFeedforward
public void setFeedforward(double kS, double kV, double kA, double kG) Description copied from class:SmartMotorControllerSet the feedforward controller.- Specified by:
setFeedforwardin classSmartMotorController- Parameters:
kS- kS; Static feedforward.kV- kV; Velocity feedforward.kA- kA; Acceleration feedforward.kG- kG; Gravity feedforward.
-
setStatorCurrentLimit
Description copied from class:SmartMotorControllerSet the stator current limit for the device.- Specified by:
setStatorCurrentLimitin classSmartMotorController- Parameters:
currentLimit- Stator current limit.
-
setSupplyCurrentLimit
Deprecated.Description copied from class:SmartMotorControllerSet the supply current limit.- Specified by:
setSupplyCurrentLimitin classSmartMotorController- Parameters:
currentLimit- Supply current limit.
-
setClosedLoopRampRate
Description copied from class:SmartMotorControllerSet the closed loop ramp rate. The ramp rate is how fast the motor can go from 0-100, measured in seconds.- Specified by:
setClosedLoopRampRatein classSmartMotorController- Parameters:
rampRate- Time from 0 to 100.
-
setOpenLoopRampRate
Description copied from class:SmartMotorControllerSet the open loop ramp rate. The ramp rate is how fast the motor can go from 0 to 100, measured in Seconds.- Specified by:
setOpenLoopRampRatein classSmartMotorController- Parameters:
rampRate- Time it takes to go from 0 to 100.
-
setMeasurementUpperLimit
Description copied from class:SmartMotorControllerSet the measurement upper limit, only works if mechanism circumference is defined.- Specified by:
setMeasurementUpperLimitin classSmartMotorController- Parameters:
upperLimit- Upper limit, will be translated to meters.
-
setMeasurementLowerLimit
Description copied from class:SmartMotorControllerSet the measurement lower limit, only works if mechanism circumference is defined.- Specified by:
setMeasurementLowerLimitin classSmartMotorController- Parameters:
lowerLimit- Lower limit, will be translated to meters.
-
setMechanismUpperLimit
Description copied from class:SmartMotorControllerSet the mechanism upper limit.- Specified by:
setMechanismUpperLimitin classSmartMotorController- Parameters:
upperLimit- Upper limit, will be translated to rotations.
-
setMechanismLowerLimit
Description copied from class:SmartMotorControllerSet the mechanism lower limit.- Specified by:
setMechanismLowerLimitin classSmartMotorController- Parameters:
lowerLimit- Lower limit, will be translated to rotations.
-
getTemperature
Description copied from class:SmartMotorControllerGet theSmartMotorControllertemperature.- Specified by:
getTemperaturein classSmartMotorController- Returns:
Temperature
-
getConfig
Description copied from class:SmartMotorControllerGet theSmartMotorControllerConfigfor theSmartMotorController- Specified by:
getConfigin classSmartMotorController- Returns:
SmartMotorControllerConfigused.
-
getMotorController
Description copied from class:SmartMotorControllerGet the Motor Controller Object passed into theSmartMotorController.- Specified by:
getMotorControllerin classSmartMotorController- Returns:
- Motor Controller object.
-
getMotorControllerConfig
Description copied from class:SmartMotorControllerGet the motor controller object config generated bySmartMotorControllerbased off theSmartMotorControllerConfig- Specified by:
getMotorControllerConfigin classSmartMotorController- Returns:
- Motor controller config.
-
getUnsupportedTelemetryFields
public Pair<Optional<List<SmartMotorControllerTelemetry.BooleanTelemetryField>>,Optional<List<SmartMotorControllerTelemetry.DoubleTelemetryField>>> getUnsupportedTelemetryFields()Description copied from class:SmartMotorControllerGet a list of unsupported telemetry fields if any exist.- Specified by:
getUnsupportedTelemetryFieldsin classSmartMotorController- Returns:
- Optional list of unsupported telemetry fields.
-
getSysIdConfig
protected SysIdRoutine.Config getSysIdConfig(Voltage maxVoltage, Velocity<VoltageUnit> stepVoltage, Time testDuration) Description copied from class:SmartMotorControllerGet the SysIdConfig which may need to have modifications based on the SmartMotorController, like TalonFX and TalonFXS to record states correctly.- Overrides:
getSysIdConfigin classSmartMotorController- Parameters:
maxVoltage- Maximum voltage of theSysIdRoutine.stepVoltage- Step voltage for the dynamic test inSysIdRoutine.testDuration- Duration of eachSysIdRoutinerun.- Returns:
SysIdRoutine.Configof theSysIdRoutineto run.
-