CTRE Phoenix C++ 5.33.1
ctre::phoenix::motorcontrol::can::TalonFXConfiguration Struct Reference

Configurables available to TalonFX. More...

#include <ctre/phoenix/motorcontrol/can/TalonFX.h>

Inheritance diagram for ctre::phoenix::motorcontrol::can::TalonFXConfiguration:
ctre::phoenix::motorcontrol::can::BaseTalonConfiguration ctre::phoenix::motorcontrol::can::BaseMotorControllerConfiguration ctre::phoenix::CustomParamConfiguration

Public Member Functions

 TalonFXConfiguration ()
 
std::string toString ()
 
std::string toString (std::string prependString)
 
- Public Member Functions inherited from ctre::phoenix::motorcontrol::can::BaseTalonConfiguration
 BaseTalonConfiguration (FeedbackDevice defaultFeedbackDevice)
 
std::string toString ()
 
std::string toString (std::string prependString)
 
- Public Member Functions inherited from ctre::phoenix::motorcontrol::can::BaseMotorControllerConfiguration
 BaseMotorControllerConfiguration ()
 
std::string toString ()
 
std::string toString (std::string prependString)
 
- Public Member Functions inherited from ctre::phoenix::CustomParamConfiguration
 CustomParamConfiguration ()
 
std::string toString ()
 
std::string toString (std::string prependString)
 

Public Attributes

SupplyCurrentLimitConfiguration supplyCurrLimit
 Supply-side current limiting. More...
 
StatorCurrentLimitConfiguration statorCurrLimit
 Stator-side current limiting. More...
 
ctre::phoenix::motorcontrol::MotorCommutation motorCommutation = ctre::phoenix::motorcontrol::MotorCommutation::Trapezoidal
 Choose the type of motor commutation. More...
 
ctre::phoenix::sensors::AbsoluteSensorRange absoluteSensorRange = ctre::phoenix::sensors::AbsoluteSensorRange::Unsigned_0_to_360
 Desired Sign / Range for the absolute position register. More...
 
double integratedSensorOffsetDegrees = 0
 Adjusts the zero point for the absolute position register. More...
 
ctre::phoenix::sensors::SensorInitializationStrategy initializationStrategy = ctre::phoenix::sensors::SensorInitializationStrategy::BootToZero
 The sensor initialization strategy to use.This will impact the behavior the next time device boots up. More...
 
- Public Attributes inherited from ctre::phoenix::motorcontrol::can::BaseTalonConfiguration
BaseTalonPIDSetConfiguration primaryPID
 Primary PID configuration. More...
 
BaseTalonPIDSetConfiguration auxiliaryPID
 Auxiliary PID configuration. More...
 
LimitSwitchSource forwardLimitSwitchSource
 Forward Limit Switch Source. More...
 
LimitSwitchSource reverseLimitSwitchSource
 Reverse Limit Switch Source. More...
 
int forwardLimitSwitchDeviceID
 Forward limit switch device ID. More...
 
int reverseLimitSwitchDeviceID
 Reverse limit switch device ID. More...
 
LimitSwitchNormal forwardLimitSwitchNormal
 Forward limit switch normally open/closed. More...
 
LimitSwitchNormal reverseLimitSwitchNormal
 Reverse limit switch normally open/closed. More...
 
FeedbackDevice sum0Term
 Feedback Device for Sum 0 Term Note the FeedbackDevice enum holds all possible sensor types. More...
 
FeedbackDevice sum1Term
 Feedback Device for Sum 1 Term Note the FeedbackDevice enum holds all possible sensor types. More...
 
FeedbackDevice diff0Term
 Feedback Device for Diff 0 Term Note the FeedbackDevice enum holds all possible sensor types. More...
 
FeedbackDevice diff1Term
 Feedback Device for Diff 1 Term Note the FeedbackDevice enum holds all possible sensor types. More...
 
- Public Attributes inherited from ctre::phoenix::motorcontrol::can::BaseMotorControllerConfiguration
double openloopRamp
 Seconds to go from 0 to full in open loop. More...
 
double closedloopRamp
 Seconds to go from 0 to full in closed loop. More...
 
double peakOutputForward
 Peak output in forward direction [0,1]. More...
 
double peakOutputReverse
 Peak output in reverse direction [-1,0]. More...
 
double nominalOutputForward
 Nominal/Minimum output in forward direction [0,1]. More...
 
double nominalOutputReverse
 Nominal/Minimum output in reverse direction [-1,0]. More...
 
double neutralDeadband
 Neutral deadband [0.001, 0.25]. More...
 
double voltageCompSaturation
 This is the max voltage to apply to the hbridge when voltage compensation is enabled. More...
 
int voltageMeasurementFilter
 Number of samples in rolling average for voltage. More...
 
ctre::phoenix::sensors::SensorVelocityMeasPeriod velocityMeasurementPeriod
 Desired period for velocity measurement. More...
 
int velocityMeasurementWindow
 Desired window for velocity measurement. More...
 
double forwardSoftLimitThreshold
 Threshold for soft limits in forward direction (in raw sensor units) More...
 
double reverseSoftLimitThreshold
 Threshold for soft limits in reverse direction (in raw sensor units) More...
 
bool forwardSoftLimitEnable
 Enable forward soft limit. More...
 
bool reverseSoftLimitEnable
 Enable reverse soft limit. More...
 
SlotConfiguration slot0
 Configuration for slot 0. More...
 
SlotConfiguration slot1
 Configuration for slot 1. More...
 
SlotConfiguration slot2
 Configuration for slot 2. More...
 
SlotConfiguration slot3
 Configuration for slot 3. More...
 
bool auxPIDPolarity
 PID polarity inversion. More...
 
FilterConfiguration remoteFilter0
 Configuration for RemoteFilter 0. More...
 
FilterConfiguration remoteFilter1
 Configuration for RemoteFilter 1. More...
 
double motionCruiseVelocity
 Motion Magic cruise velocity in raw sensor units per 100 ms. More...
 
double motionAcceleration
 Motion Magic acceleration in (raw sensor units per 100 ms) per second. More...
 
int motionCurveStrength
 Zero to use trapezoidal motion during motion magic. More...
 
int motionProfileTrajectoryPeriod
 Motion profile base trajectory period in milliseconds. More...
 
bool feedbackNotContinuous
 Determine whether feedback sensor is continuous or not. More...
 
bool remoteSensorClosedLoopDisableNeutralOnLOS
 Disable neutral'ing the motor when remote sensor is lost on CAN bus. More...
 
bool clearPositionOnLimitF
 Clear the position on forward limit. More...
 
bool clearPositionOnLimitR
 Clear the position on reverse limit. More...
 
bool clearPositionOnQuadIdx
 Clear the position on index. More...
 
bool limitSwitchDisableNeutralOnLOS
 Disable neutral'ing the motor when remote limit switch is lost on CAN bus. More...
 
bool softLimitDisableNeutralOnLOS
 Disable neutral'ing the motor when remote soft limit is lost on CAN bus. More...
 
int pulseWidthPeriod_EdgesPerRot
 Number of edges per rotation for a tachometer sensor. More...
 
int pulseWidthPeriod_FilterWindowSz
 Desired window size for a tachometer sensor. More...
 
bool trajectoryInterpolationEnable
 Enable motion profile trajectory point interpolation (defaults to true). More...
 
- Public Attributes inherited from ctre::phoenix::CustomParamConfiguration
int customParam0
 Custom Param 0. More...
 
int customParam1
 Custom Param 1. More...
 
bool enableOptimizations
 Enable optimizations for ConfigAll (defaults true) More...
 

Detailed Description

Configurables available to TalonFX.

Deprecated:
This device's Phoenix 5 API is deprecated for removal in the 2025 season. Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API. A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.

If the Phoenix 5 API must be used for this device, the device must have 22.X firmware. This firmware is available in Tuner X after selecting Phoenix 5 in the firmware year dropdown.

Constructor & Destructor Documentation

◆ TalonFXConfiguration()

ctre::phoenix::motorcontrol::can::TalonFXConfiguration::TalonFXConfiguration ( )
inline

Member Function Documentation

◆ toString() [1/2]

std::string ctre::phoenix::motorcontrol::can::TalonFXConfiguration::toString ( )
inline
Returns
String representation of all the configs

◆ toString() [2/2]

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

Member Data Documentation

◆ absoluteSensorRange

ctre::phoenix::sensors::AbsoluteSensorRange ctre::phoenix::motorcontrol::can::TalonFXConfiguration::absoluteSensorRange = ctre::phoenix::sensors::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

ctre::phoenix::sensors::SensorInitializationStrategy ctre::phoenix::motorcontrol::can::TalonFXConfiguration::initializationStrategy = ctre::phoenix::sensors::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 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

ctre::phoenix::motorcontrol::MotorCommutation ctre::phoenix::motorcontrol::can::TalonFXConfiguration::motorCommutation = ctre::phoenix::motorcontrol::MotorCommutation::Trapezoidal

Choose the type of motor commutation.

◆ statorCurrLimit

StatorCurrentLimitConfiguration ctre::phoenix::motorcontrol::can::TalonFXConfiguration::statorCurrLimit

Stator-side current limiting.

This is typically used to limit acceleration/torque and heat generation.

◆ supplyCurrLimit

SupplyCurrentLimitConfiguration ctre::phoenix::motorcontrol::can::TalonFXConfiguration::supplyCurrLimit

Supply-side current limiting.

This is typically used to prevent breakers from tripping.


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