CTRE_Phoenix 5.20.2
com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration Class Reference

Inherits com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration.

Public Member Functions

String toString ()
 
String toString (String prependString)
 
- Public Member Functions inherited from com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration
 BaseTalonConfiguration (FeedbackDevice defaultFeedbackDevice)
 
String toString ()
 
String toString (String prependString)
 
String toString ()
 
String toString (String prependString)
 
String toString ()
 
String toString (String prependString)
 

Public Attributes

SupplyCurrentLimitConfiguration supplyCurrLimit = new SupplyCurrentLimitConfiguration()
 
StatorCurrentLimitConfiguration statorCurrLimit = new StatorCurrentLimitConfiguration()
 
MotorCommutation motorCommutation = MotorCommutation.Trapezoidal
 
AbsoluteSensorRange absoluteSensorRange = AbsoluteSensorRange.Unsigned_0_to_360
 
double integratedSensorOffsetDegrees = 0
 
SensorInitializationStrategy initializationStrategy = SensorInitializationStrategy.BootToZero
 
- Public Attributes inherited from com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration
BaseTalonPIDSetConfiguration primaryPID
 
BaseTalonPIDSetConfiguration auxiliaryPID
 
LimitSwitchSource forwardLimitSwitchSource
 
LimitSwitchSource reverseLimitSwitchSource
 
int forwardLimitSwitchDeviceID
 
int reverseLimitSwitchDeviceID
 
LimitSwitchNormal forwardLimitSwitchNormal
 
LimitSwitchNormal reverseLimitSwitchNormal
 
FeedbackDevice sum0Term
 
FeedbackDevice sum1Term
 
FeedbackDevice diff0Term
 
FeedbackDevice diff1Term
 
- Public Attributes inherited from com.ctre.phoenix.motorcontrol.can.BaseMotorControllerConfiguration
double openloopRamp
 
double closedloopRamp
 
double peakOutputForward
 
double peakOutputReverse
 
double nominalOutputForward
 
double nominalOutputReverse
 
double neutralDeadband
 
double voltageCompSaturation
 
int voltageMeasurementFilter
 
SensorVelocityMeasPeriod velocityMeasurementPeriod
 
int velocityMeasurementWindow
 
double forwardSoftLimitThreshold
 
double reverseSoftLimitThreshold
 
boolean forwardSoftLimitEnable
 
boolean reverseSoftLimitEnable
 
SlotConfiguration slot0
 
SlotConfiguration slot1
 
SlotConfiguration slot2
 
SlotConfiguration slot3
 
boolean auxPIDPolarity
 
FilterConfiguration remoteFilter0
 
FilterConfiguration remoteFilter1
 
double motionCruiseVelocity
 
double motionAcceleration
 
int motionCurveStrength
 
int motionProfileTrajectoryPeriod
 
boolean feedbackNotContinuous
 
boolean remoteSensorClosedLoopDisableNeutralOnLOS
 
boolean clearPositionOnLimitF
 
boolean clearPositionOnLimitR
 
boolean clearPositionOnQuadIdx
 
boolean limitSwitchDisableNeutralOnLOS
 
boolean softLimitDisableNeutralOnLOS
 
int pulseWidthPeriod_EdgesPerRot
 
int pulseWidthPeriod_FilterWindowSz
 
boolean trajectoryInterpolationEnable
 
- Public Attributes inherited from com.ctre.phoenix.CustomParamConfiguration
int customParam0
 
int customParam1
 
boolean enableOptimizations
 

Detailed Description

Configurables available to TalonFX

Member Function Documentation

◆ toString() [1/2]

String com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.toString ( )
inline
Returns
String representation of all the configs

Reimplemented from com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration.

◆ toString() [2/2]

String com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.toString ( String  prependString)
inline
Parameters
prependStringString to prepend to all the configs
Returns
String representation of all the configs

Reimplemented from com.ctre.phoenix.motorcontrol.can.BaseTalonConfiguration.

Member Data Documentation

◆ absoluteSensorRange

AbsoluteSensorRange com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.absoluteSensorRange = AbsoluteSensorRange.Unsigned_0_to_360

Desired Sign / Range for the absolute position register. Choose unsigned for an absolute range of[0, +1) rotations, [0, 360) deg, etc. Choose signed for an absolute range of[-0.5, +0.5) rotations, [-180, +180) deg, etc.

◆ initializationStrategy

SensorInitializationStrategy com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.initializationStrategy = SensorInitializationStrategy.BootToZero

The sensor initialization strategy to use.This will impact the behavior the next time device boots up.

Pick the strategy on how to initialize the "Position" register. Depending on the mechanism, it may be desirable to auto set the Position register to match the Absolute Position(swerve for example). Or it may be desired to zero the sensor on boot(drivetrain translation sensor or a relative servo).

TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the device is reset.

◆ integratedSensorOffsetDegrees

double com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.integratedSensorOffsetDegrees = 0

Adjusts the zero point for the absolute position register. The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180) and a hard-limited mechanism may have such a discontinuity in its functional range. In which case use this config to move the discontinuity outside of the function range.

◆ motorCommutation

MotorCommutation com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.motorCommutation = MotorCommutation.Trapezoidal

Choose the type of motor commutation.

◆ statorCurrLimit

StatorCurrentLimitConfiguration com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.statorCurrLimit = new StatorCurrentLimitConfiguration()

Stator-side current limiting. This is typically used to limit acceleration/torque and heat generation.

◆ supplyCurrLimit

SupplyCurrentLimitConfiguration com.ctre.phoenix.motorcontrol.can.TalonFXConfiguration.supplyCurrLimit = new SupplyCurrentLimitConfiguration()

Supply-side current limiting. This is typically used to prevent breakers from tripping.


The documentation for this class was generated from the following file: