TalonFX

class phoenix5.TalonFX(deviceNumber: int, canbus: str = '')

Bases: BaseTalon

CTRE Talon FX Motor Controller when used on CAN Bus.

{@code
// Example usage of a TalonFX motor controller
TalonFX motor{0}; // creates a new TalonFX with ID 0

TalonFXConfiguration config;
config.supplyCurrLimit.enable = true;
config.supplyCurrLimit.triggerThresholdCurrent = 40; // the peak supply current, in amps
config.supplyCurrLimit.triggerThresholdTime = 1.5; // the time at the peak supply current before the limit triggers, in sec
config.supplyCurrLimit.currentLimit = 30; // the current to maintain if the peak supply limit is triggered
motor.ConfigAllSettings(config); // apply the config settings; this selects the quadrature encoder

motor.Set(TalonFXControlMode::PercentOutput, 0.5); // runs the motor at 50% power

std::cout << motor.GetSelectedSensorPosition() << std::endl; // prints the position of the selected sensor
std::cout << motor.GetSelectedSensorVelocity() << std::endl; // prints the velocity recorded by the selected sensor
std::cout << motor.GetMotorOutputPercent() << std::endl; // prints the percent output of the motor (0.5)
std::cout << motor.GetStatorCurrent() << std::endl; // prints the output current of the motor

ErrorCode error = motor.GetLastError(); // gets the last error generated by the motor controller
Faults faults;
ErrorCode faultsError = motor.GetFaults(faults); // fills faults with the current motor controller faults; returns the last error generated

motor.SetStatusFramePeriod(StatusFrameEnhanced::Status_2_Feedback0, 10); // changes the period of the Status 2 frame (GetSelectedSensor*()) to 10ms
}

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.

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.

See also

WPI_TalonFX

Constructor for a Talon

Parameters:
  • deviceNumber – CAN Device ID of TalonFX

  • canbus – Name of the CANbus; can be a SocketCAN interface (on Linux), or a CANivore device name or serial number

configAllSettings(allConfigs: phoenix5._ctre.TalonFXConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Configures all persistent settings.

Parameters:
  • allConfigs – Object with all of the persistant settings

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configGetMotorCommutation(motorCommutation: phoenix5._ctre.MotorCommutation, timeoutMs: int = 0) phoenix5._ctre.ErrorCode
Parameters:

timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.

Returns:

The motor commutation type.

configGetStatorCurrentLimit(currLimitConfigsToFill: phoenix5._ctre.StatorCurrentLimitConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Gets the stator (output) current limit configuration.

Parameters:
  • currLimitConfigsToFill – Configuration object to fill with read values.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.

Returns:

Error Code generated by function. 0 indicates no error.

configGetSupplyCurrentLimit(currLimitConfigsToFill: phoenix5._ctre.SupplyCurrentLimitConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Gets the supply current limit configuration.

Parameters:
  • currLimitConfigsToFill – Configuration object to fill with read values.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out.

Returns:

Error Code generated by function. 0 indicates no error.

configIntegratedSensorAbsoluteRange(absoluteSensorRange: phoenix5._ctre.sensors.AbsoluteSensorRange, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Sets the signage and range of the “Absolute Position” signal. 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…

Parameters:
  • absoluteSensorRange – Desired Sign/Range for the absolute position register.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configIntegratedSensorInitializationStrategy(initializationStrategy: phoenix5._ctre.sensors.SensorInitializationStrategy, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Pick the strategy on how to initialize the integrated sensor absolute 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 product is reset.

Parameters:
  • initializationStrategy – The sensor initialization strategy to use. This will impact the behavior the next time product boots up.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configIntegratedSensorOffset(offsetDegrees: float, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

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.

Parameters:
  • offsetDegrees – Offset in degrees (unit string and coefficient DO NOT apply for this config).

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configMotorCommutation(motorCommutation: phoenix5._ctre.MotorCommutation, timeoutMs: int = 0) phoenix5._ctre.ErrorCode

Configure the motor commutation type.

Parameters:
  • motorCommutation – Motor Commutation Type.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

configSelectedFeedbackSensor(*args, **kwargs)

Overloaded function.

  1. configSelectedFeedbackSensor(self: phoenix5._ctre.TalonFX, feedbackDevice: phoenix5._ctre.TalonFXFeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

Select the feedback device for the motor controller.

Parameters:
  • feedbackDevice – Talon FX Feedback Device to select.

  • pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

  1. configSelectedFeedbackSensor(self: phoenix5._ctre.TalonFX, feedbackDevice: phoenix5._ctre.FeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

  2. configSelectedFeedbackSensor(self: phoenix5._ctre.TalonFX, feedbackDevice: phoenix5._ctre.RemoteFeedbackDevice, pidIdx: int = 0, timeoutMs: int = 0) -> phoenix5._ctre.ErrorCode

configStatorCurrentLimit(currLimitConfigs: phoenix5._ctre.StatorCurrentLimitConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Configures the stator (output) current limit.

Parameters:
  • currLimitCfg – Current limit configuration

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configSupplyCurrentLimit(currLimitConfigs: phoenix5._ctre.SupplyCurrentLimitConfiguration, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Configures the supply-side current limit.

Parameters:
  • currLimitCfg – Current limit configuration

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

Returns:

Error Code generated by function. 0 indicates no error.

configurePID(pid: phoenix5._ctre.TalonFXPIDSetConfiguration, pidIdx: int = 0, timeoutMs: int = 50) phoenix5._ctre.ErrorCode

Sets all PID persistant settings.

Parameters:
  • pid – Object with all of the PID set persistant settings

  • pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

getAllConfigs(allConfigs: phoenix5._ctre.TalonFXConfiguration, timeoutMs: int = 50) None

Gets all persistant settings.

Parameters:
  • allConfigs – Object with all of the persistant settings

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

getPIDConfigs(pid: phoenix5._ctre.TalonFXPIDSetConfiguration, pidIdx: int = 0, timeoutMs: int = 50) None

Gets all PID set persistant settings.

Parameters:
  • pid – Object with all of the PID set persistant settings

  • pidIdx – 0 for Primary closed-loop. 1 for auxiliary closed-loop.

  • timeoutMs – Timeout value in ms. If nonzero, function will wait for config success and report an error if it times out. If zero, no blocking or checking is performed.

getSensorCollection() phoenix5._ctre.TalonFXSensorCollection
Returns:

object that can get/set individual RAW sensor values.

getSimCollection() phoenix5._ctre.TalonFXSimCollection
Returns:

object that can set simulation inputs.

set(*args, **kwargs)

Overloaded function.

  1. set(self: phoenix5._ctre.TalonFX, mode: phoenix5._ctre.TalonFXControlMode, value: float) -> None

Sets the appropriate output on the talon, depending on the mode.

  • Standard Driving Example:

  • _talonLeft.set(ControlMode.PercentOutput, leftJoy);

  • _talonRght.set(ControlMode.PercentOutput, rghtJoy);

Parameters:
  • mode – The output mode to apply. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. In Follower mode, the output value is the integer device ID of the talon to duplicate.

  • value – The setpoint value, as described above.

  1. set(self: phoenix5._ctre.TalonFX, mode: phoenix5._ctre.TalonFXControlMode, demand0: float, demand1Type: phoenix5._ctre.DemandType, demand1: float) -> None

Arcade Drive Example: * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn); * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);

  • Drive Straight Example:

  • Note: Selected Sensor Configuration is necessary for both PID0 and PID1.

  • _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);

  • _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);

  • Drive Straight to a Distance Example:

  • Note: Other configurations (sensor selection, PID gains, etc.) need to be set.

  • _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);

  • _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);

Parameters:
  • mode – Sets the appropriate output on the talon, depending on the mode.

  • demand0 – The output value to apply. such as advanced feed forward and/or auxiliary close-looping in firmware. In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped. In Current mode, output value is in amperes. In Velocity mode, output value is in position change / 100ms. In Position mode, output value is in encoder ticks or an analog value, depending on the sensor. See In Follower mode, the output value is the integer device ID of the talon to duplicate.

  • demand1Type – The demand type for demand1. Neutral: Ignore demand1 and apply no change to the demand0 output. AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary PID is always executed as standard Position PID control. ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the * demand0 output. In PercentOutput the demand0 output is the motor output, and in closed-loop modes the demand0 output is the output of PID0.

  • demand1 – Supplmental output value. AuxPID: Target position in Sensor Units ArbitraryFeedForward: Percent Output between -1.0 and 1.0

  1. set(self: phoenix5._ctre.TalonFX, mode: phoenix5._ctre.ControlMode, value: float) -> None

  2. set(self: phoenix5._ctre.TalonFX, mode: phoenix5._ctre.ControlMode, demand0: float, demand1Type: phoenix5._ctre.DemandType, demand1: float) -> None

setInverted(*args, **kwargs)

Overloaded function.

  1. setInverted(self: phoenix5._ctre.TalonFX, invertType: phoenix5._ctre.TalonFXInvertType) -> None

Inverts the hbridge output of the motor controller in relation to the master if present

This does not impact sensor phase and should not be used to correct sensor polarity.

This will allow you to either: - Not invert the motor - Invert the motor - Always follow the master regardless of master’s inversion - Always oppose the master regardless of master’s inversion

Parameters:

invertType – Invert state to set.

  1. setInverted(self: phoenix5._ctre.TalonFX, invertType: phoenix5._ctre.InvertType) -> None

  2. setInverted(self: phoenix5._ctre.TalonFX, bInvert: bool) -> None