CTRE Phoenix C++ 5.33.1
ctre::phoenix::motorcontrol::TalonFXSensorCollection Class Reference

Collection of sensors available to the Talon FX. More...

#include <ctre/phoenix/motorcontrol/TalonFXSensorCollection.h>

Public Member Functions

 TalonFXSensorCollection (ctre::phoenix::motorcontrol::can::BaseTalon &motorController)
 Constructor for TalonFXSensorCollection. More...
 
double GetIntegratedSensorPosition ()
 Get the IntegratedSensor position of the Talon FX, regardless of whether it is actually being used for feedback. More...
 
double GetIntegratedSensorAbsolutePosition ()
 Get the IntegratedSensor absolute position of the Talon FX, regardless of whether it is actually being used for feedback. More...
 
double GetIntegratedSensorVelocity ()
 Get the IntegratedSensor velocity of the Talon FX, regardless of whether it is actually being used for feedback. More...
 
ErrorCode SetIntegratedSensorPosition (double newPosition, int timeoutMs=0)
 Set the IntegratedSensor reported position. More...
 
ErrorCode SetIntegratedSensorPositionToAbsolute (int timeoutMs=0)
 Set the IntegratedSensor reported position based on the absolute position. More...
 
int IsFwdLimitSwitchClosed ()
 Is forward limit switch closed. More...
 
int IsRevLimitSwitchClosed ()
 Is reverse limit switch closed. More...
 

Detailed Description

Collection of sensors available to the Talon FX.

For best performance and update-rate, we recommend using the configSelectedFeedbackSensor() and getSelectedSensor*() routines. However there are occasions where accessing raw sensor values may be useful or convenient. Particularly if you are seeding one sensor based on another, or need to circumvent sensor-phase.

Use the GetTalonFXSensorCollection() routine inside your motor controller to create a sensor collection.

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

◆ TalonFXSensorCollection()

ctre::phoenix::motorcontrol::TalonFXSensorCollection::TalonFXSensorCollection ( ctre::phoenix::motorcontrol::can::BaseTalon motorController)

Constructor for TalonFXSensorCollection.

Parameters
motorControllerTalon Motor Controller to connect Collection to

Member Function Documentation

◆ GetIntegratedSensorAbsolutePosition()

double ctre::phoenix::motorcontrol::TalonFXSensorCollection::GetIntegratedSensorAbsolutePosition ( )

Get the IntegratedSensor absolute position of the Talon FX, regardless of whether it is actually being used for feedback.

This will be within one rotation (2048 units). The signage and range will depend on the configuration. Note : Future versions of software may support scaling features (rotations, radians, degrees, etc) depending on the configuration.

This method relies on the Status 21 message, which has a default period of 240ms. For more information, see: https://phoenix-documentation.readthedocs.io/en/latest/ch18_CommonAPI.html

Returns
the IntegratedSensor absolute position.

◆ GetIntegratedSensorPosition()

double ctre::phoenix::motorcontrol::TalonFXSensorCollection::GetIntegratedSensorPosition ( )

Get the IntegratedSensor position of the Talon FX, regardless of whether it is actually being used for feedback.

The units are 2048 per rotation. Note : Future versions of software may support scaling features (rotations, radians, degrees, etc) depending on the configuration.

This method relies on the Status 21 message, which has a default period of 240ms. For more information, see: https://phoenix-documentation.readthedocs.io/en/latest/ch18_CommonAPI.html

Returns
the IntegratedSensor position.

◆ GetIntegratedSensorVelocity()

double ctre::phoenix::motorcontrol::TalonFXSensorCollection::GetIntegratedSensorVelocity ( )

Get the IntegratedSensor velocity of the Talon FX, regardless of whether it is actually being used for feedback.


One unit represents one position unit per 100ms (2048 position units per 100ms). The signage and range will depend on the configuration. Note : Future versions of software may support scaling features (rotations, radians, degrees, etc) depending on the configuration.

This method relies on the Status 21 message, which has a default period of 240ms. For more information, see: https://phoenix-documentation.readthedocs.io/en/latest/ch18_CommonAPI.html

Returns
the IntegratedSensor velocity.

◆ IsFwdLimitSwitchClosed()

int ctre::phoenix::motorcontrol::TalonFXSensorCollection::IsFwdLimitSwitchClosed ( )

Is forward limit switch closed.

This method relies on the Status 1 message, which has a default period of 10ms. For more information, see: https://phoenix-documentation.readthedocs.io/en/latest/ch18_CommonAPI.html

Returns
'1' iff forward limit switch is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.

◆ IsRevLimitSwitchClosed()

int ctre::phoenix::motorcontrol::TalonFXSensorCollection::IsRevLimitSwitchClosed ( )

Is reverse limit switch closed.

This method relies on the Status 1 message, which has a default period of 10ms. For more information, see: https://phoenix-documentation.readthedocs.io/en/latest/ch18_CommonAPI.html

Returns
'1' iff reverse limit switch is closed, 0 iff switch is open. This function works regardless if limit switch feature is enabled. Remote limit features do not impact this routine.

◆ SetIntegratedSensorPosition()

ErrorCode ctre::phoenix::motorcontrol::TalonFXSensorCollection::SetIntegratedSensorPosition ( double  newPosition,
int  timeoutMs = 0 
)

Set the IntegratedSensor reported position.

Typically this is used to "zero" the sensor. This only works with IntegratedSensor. To set the selected sensor position regardless of what type it is, see SetSelectedSensorPosition in the motor controller class.

Parameters
newPositionThe position value to apply to the sensor.
timeoutMsTimeout 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.

◆ SetIntegratedSensorPositionToAbsolute()

ErrorCode ctre::phoenix::motorcontrol::TalonFXSensorCollection::SetIntegratedSensorPositionToAbsolute ( int  timeoutMs = 0)

Set the IntegratedSensor reported position based on the absolute position.

This can also be done automatically on power boot depending on configuration.

Parameters
timeoutMsTimeout 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.

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