CTRE Phoenix C++ 5.33.1
ctre::phoenix::motorcontrol Namespace Reference

namespace motorcontrol More...

Namespaces

namespace  can
 namespace can
 
namespace  lowlevel
 namespace lowlevel
 

Classes

class  ControlFrameRoutines
 Class to handle promotion of controlFrame to controlFrameEnhanced. More...
 
class  DeviceCatalog
 Class to keep track of multiple devices. More...
 
struct  Faults
 All the faults available to motor controllers. More...
 
class  FeedbackDeviceRoutines
 Class to handle feedback device routines. More...
 
class  GroupMotorControllers
 Group of motor controllers. More...
 
class  IFollower
 Interface for followers. More...
 
class  IMotorController
 Interface for motor controllers. More...
 
class  IMotorControllerEnhanced
 Interface for enhanced motor controllers. More...
 
class  LimitSwitchRoutines
 Class to handle various functions regarding limit switches. More...
 
class  RemoteSensorSourceRoutines
 Class used to get string representation of a remote sensor source. More...
 
class  SensorCollection
 Collection of sensors available to a motor controller. More...
 
class  SensorTermRoutines
 Class to handle routines specific to SensorTerm. More...
 
struct  StatorCurrentLimitConfiguration
 Describes the desired stator current limiting behavior. More...
 
class  StatusFrameRoutines
 Class to allow conversion from StatusFrame to EnhancedStatusFrame. More...
 
struct  StickyFaults
 All the sticky faults available to motor controllers. More...
 
struct  SupplyCurrentLimitConfiguration
 Describes the desired stator current limiting behavior. More...
 
class  TalonFXSensorCollection
 Collection of sensors available to the Talon FX. More...
 
class  TalonFXSimCollection
 Collection of simulation commands available to a TalonFX motor controller. More...
 
class  TalonSRXSimCollection
 Collection of simulation commands available to a TalonSRX motor controller. More...
 
class  VelocityMeasPeriodRoutines
 Class to handle routines specific to VelocityMeasPeriod. More...
 
class  VictorSPXSimCollection
 Collection of simulation commands available to a VictorSPX motor controller. More...
 
class  WPI_AutoFeedEnable
 

Enumerations

enum  DemandType { DemandType_Neutral = 0 , DemandType_AuxPID = 1 , DemandType_ArbitraryFeedForward = 2 }
 How to interpret a demand value. More...
 
enum  VelocityMeasPeriod {
  Period_1Ms = 1 , Period_2Ms = 2 , Period_5Ms = 5 , Period_10Ms = 10 ,
  Period_20Ms = 20 , Period_25Ms = 25 , Period_50Ms = 50 , Period_100Ms = 100
}
 Velocity Measurement Periods. More...
 
enum  StatusFrameEnhanced {
  Status_1_General = 0x1400 , Status_2_Feedback0 = 0x1440 , Status_4_AinTempVbat = 0x14C0 , Status_6_Misc = 0x1540 ,
  Status_7_CommStatus = 0x1580 , Status_9_MotProfBuffer = 0x1600 , Status_10_MotionMagic = 0x1640 , Status_10_Targets = 0x1640 ,
  Status_12_Feedback1 = 0x16C0 , Status_13_Base_PIDF0 = 0x1700 , Status_14_Turn_PIDF1 = 0x1740 , Status_15_FirmwareApiStatus = 0x1780 ,
  Status_15_FirmareApiStatus = 0x1780 , Status_17_Targets1 = 0x1C00 , Status_3_Quadrature = 0x1480 , Status_8_PulseWidth = 0x15C0 ,
  Status_11_UartGadgeteer = 0x1680 , Status_Brushless_Current = 0x1240 , Status_21_FeedbackIntegrated = 0x2500
}
 The different status frames available to enhanced motor controllers. More...
 
enum  StatusFrame {
  Status_1_General_ = 0x1400 , Status_2_Feedback0_ = 0x1440 , Status_4_AinTempVbat_ = 0x14C0 , Status_6_Misc_ = 0x1540 ,
  Status_7_CommStatus_ = 0x1580 , Status_9_MotProfBuffer_ = 0x1600 , Status_10_MotionMagic_ = 0x1640 , Status_10_Targets_ = 0x1640 ,
  Status_12_Feedback1_ = 0x16C0 , Status_13_Base_PIDF0_ = 0x1700 , Status_14_Turn_PIDF1_ = 0x1740 , Status_15_FirmwareApiStatus_ = 0x1780 ,
  Status_15_FirmareApiStatus_ = 0x1780 , Status_17_Targets1_ = 0x1C00
}
 The different status frames available to motor controllers. More...
 
enum class  SensorTerm { SensorTerm_Sum0 , SensorTerm_Sum1 , SensorTerm_Diff0 , SensorTerm_Diff1 }
 Choose the sensor term for a motor controller. More...
 
enum  FollowerType { FollowerType_PercentOutput = 0 , FollowerType_AuxOutput1 }
 Choose the type of follower. More...
 
enum  ControlFrame { Control_3_General = 0x040080 , Control_4_Advanced = 0x0400C0 , Control_6_MotProfAddTrajPoint = 0x040140 }
 Control Frames for motor controllers. More...
 
enum  ControlFrameEnhanced { Control_3_General_ = 0x040080 , Control_4_Advanced_ = 0x0400c0 , Control_5_FeedbackOutputOverride_ = 0x040100 , Control_6_MotProfAddTrajPoint_ = 0x040140 }
 Control Frames for enhanced motor controllers. More...
 
enum  LimitSwitchSource {
  LimitSwitchSource_FeedbackConnector = 0 , LimitSwitchSource_RemoteTalon = 1 , LimitSwitchSource_RemoteTalonSRX = LimitSwitchSource_RemoteTalon , LimitSwitchSource_RemoteCANifier = 2 ,
  LimitSwitchSource_Deactivated = 3
}
 Limit switch source enum. More...
 
enum  RemoteLimitSwitchSource {
  RemoteLimitSwitchSource_FactoryDefaultOff = 0 , RemoteLimitSwitchSource_RemoteTalon = 1 , RemoteLimitSwitchSource_RemoteTalonSRX = RemoteLimitSwitchSource_RemoteTalon , RemoteLimitSwitchSource_RemoteCANifier = 2 ,
  RemoteLimitSwitchSource_Deactivated = 3
}
 Remote Limit switch source enum. More...
 
enum  LimitSwitchNormal { LimitSwitchNormal_NormallyOpen = 0 , LimitSwitchNormal_NormallyClosed = 1 , LimitSwitchNormal_Disabled = 2 }
 Choose whether the limit switch is normally open or normally closed. More...
 
enum class  InvertType { None = 0 , InvertMotorOutput = 1 , FollowMaster = 2 , OpposeMaster = 3 }
 Choose the invert type of the motor controller. More...
 
enum class  TalonFXInvertType { CounterClockwise = 0 , Clockwise = 1 , FollowMaster = 2 , OpposeMaster = 3 }
 Choose the invert type for a Talon FX based integrated motor controller. More...
 
enum class  FeedbackDevice {
  QuadEncoder = 0 , IntegratedSensor = 1 , Analog = 2 , Tachometer = 4 ,
  PulseWidthEncodedPosition = 8 , SensorSum = 9 , SensorDifference = 10 , RemoteSensor0 = 11 ,
  RemoteSensor1 = 12 , None = 14 , SoftwareEmulatedSensor = 15 , CTRE_MagEncoder_Absolute = PulseWidthEncodedPosition ,
  CTRE_MagEncoder_Relative = QuadEncoder
}
 Choose the feedback device for a motor controller. More...
 
enum class  TalonSRXFeedbackDevice {
  QuadEncoder = 0 , Analog = 2 , Tachometer = 4 , PulseWidthEncodedPosition = 8 ,
  SensorSum = 9 , SensorDifference = 10 , RemoteSensor0 = 11 , RemoteSensor1 = 12 ,
  None = 14 , SoftwareEmulatedSensor = 15 , CTRE_MagEncoder_Absolute = PulseWidthEncodedPosition , CTRE_MagEncoder_Relative = QuadEncoder
}
 Choose the feedback device for a Talon SRX. More...
 
enum class  TalonFXFeedbackDevice {
  IntegratedSensor = 1 , SensorSum = 9 , SensorDifference = 10 , RemoteSensor0 = 11 ,
  RemoteSensor1 = 12 , None = 14 , SoftwareEmulatedSensor = 15
}
 Choose the feedback device for a Talon FX/Falcon 500. More...
 
enum class  RemoteFeedbackDevice {
  RemoteFeedbackDevice_FactoryDefaultOff = 0 , FactoryDefaultOff = RemoteFeedbackDevice_FactoryDefaultOff , RemoteFeedbackDevice_SensorSum = 9 , SensorSum = RemoteFeedbackDevice_SensorSum ,
  RemoteFeedbackDevice_SensorDifference = 10 , SensorDifference = RemoteFeedbackDevice_SensorDifference , RemoteFeedbackDevice_RemoteSensor0 = 11 , RemoteSensor0 = RemoteFeedbackDevice_RemoteSensor0 ,
  RemoteFeedbackDevice_RemoteSensor1 = 12 , RemoteSensor1 = RemoteFeedbackDevice_RemoteSensor1 , RemoteFeedbackDevice_None = 14 , None = RemoteFeedbackDevice_None ,
  RemoteFeedbackDevice_SoftwareEmulatedSensor = 15 , SoftwareEmulatedSensor = RemoteFeedbackDevice_SoftwareEmulatedSensor
}
 Choose the remote feedback device for a motor controller. More...
 
enum class  MotorCommutation { Trapezoidal = 0 }
 Choose the type of motor commutation. More...
 
enum class  RemoteSensorSource {
  RemoteSensorSource_Off , RemoteSensorSource_TalonSRX_SelectedSensor , RemoteSensorSource_Pigeon_Yaw , RemoteSensorSource_Pigeon_Pitch ,
  RemoteSensorSource_Pigeon_Roll , RemoteSensorSource_CANifier_Quadrature , RemoteSensorSource_CANifier_PWMInput0 , RemoteSensorSource_CANifier_PWMInput1 ,
  RemoteSensorSource_CANifier_PWMInput2 , RemoteSensorSource_CANifier_PWMInput3 , RemoteSensorSource_GadgeteerPigeon_Yaw , RemoteSensorSource_GadgeteerPigeon_Pitch ,
  RemoteSensorSource_GadgeteerPigeon_Roll , RemoteSensorSource_CANCoder , RemoteSensorSource_TalonFX_SelectedSensor = RemoteSensorSource_TalonSRX_SelectedSensor
}
 Choose the remote sensor source for a motor controller. More...
 
enum  NeutralMode { EEPROMSetting = 0 , Coast = 1 , Brake = 2 }
 Choose the neutral mode for a motor controller. More...
 
enum class  ControlMode {
  PercentOutput = 0 , Position = 1 , Velocity = 2 , Current = 3 ,
  Follower = 5 , MotionProfile = 6 , MotionMagic = 7 , MotionProfileArc = 10 ,
  MusicTone = 13 , Disabled = 15
}
 Choose the control mode for a motor controller. More...
 
enum class  TalonFXControlMode {
  PercentOutput = 0 , Position = 1 , Velocity = 2 , Current = 3 ,
  Follower = 5 , MotionProfile = 6 , MotionMagic = 7 , MotionProfileArc = 10 ,
  MusicTone = 13 , Disabled = 15
}
 Choose the control mode for a TalonFX / Falcon 500. More...
 
enum class  TalonSRXControlMode {
  PercentOutput = 0 , Position = 1 , Velocity = 2 , Current = 3 ,
  Follower = 5 , MotionProfile = 6 , MotionMagic = 7 , MotionProfileArc = 10 ,
  Disabled = 15
}
 Choose the control mode for a Talon SRX. More...
 
enum class  VictorSPXControlMode {
  PercentOutput = 0 , Position = 1 , Velocity = 2 , Follower = 5 ,
  MotionProfile = 6 , MotionMagic = 7 , MotionProfileArc = 10 , Disabled = 15
}
 Choose the control mode for a Victor SPX. More...
 

Detailed Description

namespace motorcontrol

Enumeration Type Documentation

◆ ControlFrame

Control Frames for motor controllers.

Enumerator
Control_3_General 

Control.

Control_4_Advanced 

Advanced Control.

Control_6_MotProfAddTrajPoint 

Trajectory points.

◆ ControlFrameEnhanced

Control Frames for enhanced motor controllers.

Enumerator
Control_3_General_ 

Control.

Control_4_Advanced_ 

Advanced Control.

Control_5_FeedbackOutputOverride_ 

Override feedback output.

Control_6_MotProfAddTrajPoint_ 

Trajectory points.

◆ ControlMode

Choose the control mode for a motor controller.

Consult product specific documentation to determine what is available/supported.

Enumerator
PercentOutput 

Percent output [-1,1].

Position 

Position closed loop.

Velocity 

Velocity closed loop.

Current 

Input current closed loop.

Follower 

Follow other motor controller.

MotionProfile 

Motion Profile.

MotionMagic 

Motion Magic.

MotionProfileArc 

Motion Profile with auxiliary output.

MusicTone 

Plays a single tone.

Frequency (hz) is passed into set.

Disabled 

Disable Motor Controller.

◆ DemandType

How to interpret a demand value.

Enumerator
DemandType_Neutral 

Ignore the demand value and apply neutral/no-change.

DemandType_AuxPID 

When closed-looping, set the target of the aux PID loop to the demand value.

When following, follow the processed output of the combined primary/aux PID output of the master. The demand value is ignored. Although it is much cleaner to use the 2-param Follow() in such cases. Target value of Aux PID loop 1.

DemandType_ArbitraryFeedForward 

When closed-looping, add demand arbitrarily to the closed-loop output.

Simply add to the output

◆ FeedbackDevice

Choose the feedback device for a motor controller.

Consult product specific documentation to determine what is available/supported.

Enumerator
QuadEncoder 

Quadrature encoder.

IntegratedSensor 

TalonFX supports an integrated sensor.

Analog 

Analog potentiometer/encoder.

Tachometer 

Tachometer.

PulseWidthEncodedPosition 

CTRE Mag Encoder in Absolute mode or any other device that uses PWM to encode its output.

SensorSum 

Sum0 + Sum1.

SensorDifference 

Diff0 - Diff1.

RemoteSensor0 

Sensor configured in RemoteFilter0.

RemoteSensor1 

Sensor configured in RemoteFilter1.

None 

Position and velocity will read 0.

SoftwareEmulatedSensor 

Motor Controller will fake a sensor based on applied motor output.

CTRE_MagEncoder_Absolute 

CTR mag encoder configured in absolute, is the same as a PWM sensor.

CTRE_MagEncoder_Relative 

CTR mag encoder configured in relative, is the same as an quadrature encoder sensor.

◆ FollowerType

Choose the type of follower.

Enumerator
FollowerType_PercentOutput 

Follow the percentOutput the master is using.

FollowerType_AuxOutput1 

Follow the auxiliary output the master is calculating.

Used for 2-axis control. This typically means apply PID0 - PID1 from master.

◆ InvertType

Choose the invert type of the motor controller.

None is the equivalent of SetInverted(false), where positive request yields positive voltage on M+. InvertMotorOutput is the equivelant of SetInverted(true), where positive request yields positive voltage on M-. FollowMaster/OpposeMaster will match/oppose a master Talon/Victor. This requires device to be configured as a follower.

Enumerator
None 

Same as SetInverted(false)

InvertMotorOutput 

Same as SetInverted(true)

FollowMaster 

Follow the invert of the master this MC is following.

OpposeMaster 

Opposite of the invert of the master this MC is following.

◆ LimitSwitchNormal

Choose whether the limit switch is normally open or normally closed.

Enumerator
LimitSwitchNormal_NormallyOpen 

Limit Switch is tripped when the circuit is closed.

LimitSwitchNormal_NormallyClosed 

Limit Switch is tripped when the circuit is open.

LimitSwitchNormal_Disabled 

Limit switch is disabled.

◆ LimitSwitchSource

Limit switch source enum.

Enumerator
LimitSwitchSource_FeedbackConnector 

Limit switch directly connected to motor controller.

LimitSwitchSource_RemoteTalon 

Use Limit switch connected to Talon on CAN.

LimitSwitchSource_RemoteTalonSRX 

Use Limit switch connected to TalonSRX on CAN.

LimitSwitchSource_RemoteCANifier 

User Limit switch connected to CANifier.

LimitSwitchSource_Deactivated 

Don't use a limit switch.

◆ MotorCommutation

Choose the type of motor commutation.

This is for products that support selectable commutation strategies.

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.

Enumerator
Trapezoidal 

Trapezoidal Commutation.

◆ NeutralMode

Choose the neutral mode for a motor controller.

Enumerator
EEPROMSetting 

Use the NeutralMode that is set in the MC's persistent storage.

Coast 

When commanded to neutral, motor leads are set to high-impedance, allowing mechanism to coast.

Brake 

When commanded to neutral, motor leads are commonized electrically to reduce motion.

◆ RemoteFeedbackDevice

Choose the remote feedback device for a motor controller.

Enumerator
RemoteFeedbackDevice_FactoryDefaultOff 

[[deprecated("Use None instead.")]] Factory default setting for non-enhanced motor controllers

FactoryDefaultOff 

[[deprecated("Use None instead.")]] Factory default setting for non-enhanced motor controllers

RemoteFeedbackDevice_SensorSum 

[[deprecated("Use SensorSum instead.")]] Use Sum0 + Sum1

SensorSum 

Use Sum0 + Sum1.

RemoteFeedbackDevice_SensorDifference 

[[deprecated("Use SensorDifference instead.")]] Use Diff0 - Diff1

SensorDifference 

Use Diff0 - Diff1.

RemoteFeedbackDevice_RemoteSensor0 

[[deprecated("Use RemoteSensor0 instead.")]] Use the sensor configured in filter0

RemoteSensor0 

Use the sensor configured in filter0.

RemoteFeedbackDevice_RemoteSensor1 

[[deprecated("Use RemoteSensor1 instead.")]] Use the sensor configured in filter1

RemoteSensor1 

Use the sensor configured in filter1.

RemoteFeedbackDevice_None 

[[deprecated("Use None instead.")]] Position and velocity will read 0.

None 

Position and velocity will read 0.

RemoteFeedbackDevice_SoftwareEmulatedSensor 

[[deprecated("Use SoftwareEmulatedSensor instead.")]] Motor Controller will fake a sensor based on applied motor output.

SoftwareEmulatedSensor 

Motor Controller will fake a sensor based on applied motor output.

◆ RemoteLimitSwitchSource

Remote Limit switch source enum.

Enumerator
RemoteLimitSwitchSource_FactoryDefaultOff 

Don't use limit switch, this is the factory default value.

RemoteLimitSwitchSource_RemoteTalon 

Use Limit switch connected to Talon on CAN.

RemoteLimitSwitchSource_RemoteTalonSRX 

Use Limit switch connected to TalonSRX on CAN.

RemoteLimitSwitchSource_RemoteCANifier 

User Limit switch connected to CANifier.

RemoteLimitSwitchSource_Deactivated 

Don't use a limit switch.

◆ RemoteSensorSource

Choose the remote sensor source for a motor controller.

Enumerator
RemoteSensorSource_Off 

Don't use a sensor.

RemoteSensorSource_TalonSRX_SelectedSensor 

Use a sensor connected to a TalonSRX and configured on the TalonSRX.

RemoteSensorSource_Pigeon_Yaw 

Use a CAN Pigeon's Yaw value.

RemoteSensorSource_Pigeon_Pitch 

Use a CAN Pigeon's Pitch value.

RemoteSensorSource_Pigeon_Roll 

Use a CAN Pigeon's Roll value.

RemoteSensorSource_CANifier_Quadrature 

Use a quadrature sensor connected to a CANifier.

RemoteSensorSource_CANifier_PWMInput0 

Use a PWM sensor connected to CANifier's PWM0.

RemoteSensorSource_CANifier_PWMInput1 

Use a PWM sensor connected to CANifier's PWM1.

RemoteSensorSource_CANifier_PWMInput2 

Use a PWM sensor connected to CANifier's PWM2.

RemoteSensorSource_CANifier_PWMInput3 

Use a PWM sensor connected to CANifier's PWM3.

RemoteSensorSource_GadgeteerPigeon_Yaw 

Use the yaw value of a pigeon connected to a talon over ribbon cable.

RemoteSensorSource_GadgeteerPigeon_Pitch 

Use the pitch value of a pigeon connected to a talon over ribbon cable.

RemoteSensorSource_GadgeteerPigeon_Roll 

Use the roll value of a pigeon connected to a talon over ribbon cable.

RemoteSensorSource_CANCoder 

Use CANCoder.

RemoteSensorSource_TalonFX_SelectedSensor 

Remote Sensor Source 14 is reserved.

Use a sensor connected to a TalonFX and configured on the TalonFX

◆ SensorTerm

Choose the sensor term for a motor controller.

Enumerator
SensorTerm_Sum0 

Choose Sum0 for a term.

SensorTerm_Sum1 

Choose Sum1 for a term.

SensorTerm_Diff0 

Choose Diff0 for a term.

SensorTerm_Diff1 

Choose Diff1 for a term.

◆ StatusFrame

The different status frames available to motor controllers.

Enumerator
Status_1_General_ 

General Status.

Status_2_Feedback0_ 

Main controller feedback.

Status_4_AinTempVbat_ 

Analog sensor, motor controller temperature, and voltage at input leads.

Status_6_Misc_ 

Miscellaneous signals.

Status_7_CommStatus_ 

Communication status to controller.

Status_9_MotProfBuffer_ 

Motion profile buffer status.

Status_10_MotionMagic_ 

Old name for Status 10.

Use

See also
Status_10_Targets instead.
Status_10_Targets_ 

Correct name for Status 10.

Functionally equivalent to

See also
Status_10_MotionMagic
Status_12_Feedback1_ 

Secondary controller feedback.

Status_13_Base_PIDF0_ 

Base PID.

Status_14_Turn_PIDF1_ 

Auxiliary PID.

Status_15_FirmwareApiStatus_ 

Firmware & API status information.

Status_15_FirmareApiStatus_ 

Firmware & API status information [[deprecated("Use Status_15_FirmwareApiStatus_ instead.")]].

Status_17_Targets1_ 

MotionProfile Targets for Auxiliary PID1.

◆ StatusFrameEnhanced

The different status frames available to enhanced motor controllers.

Enumerator
Status_1_General 

General Status.

Status_2_Feedback0 

Feedback for selected sensor on primary PID[0].

Status_4_AinTempVbat 

Analog sensor, motor controller temperature, and voltage at input leads.

Status_6_Misc 

Miscellaneous signals.

Status_7_CommStatus 

Communication status.

Status_9_MotProfBuffer 

Motion profile buffer status.

Status_10_MotionMagic 

Old name for Status 10.

Use

See also
Status_10_Targets instead.
Status_10_Targets 

Correct name for Status 10.

Functionally equivalent to

See also
Status_10_MotionMagic
Status_12_Feedback1 

Feedback for selected sensor on aux PID[1].

Status_13_Base_PIDF0 

Primary PID.

Status_14_Turn_PIDF1 

Auxiliary PID.

Status_15_FirmwareApiStatus 

Firmware & API status information.

Status_15_FirmareApiStatus 

Firmware & API status information [[deprecated("Use Status_15_FirmwareApiStatus instead.")]].

Status_17_Targets1 

MotionProfile Targets for Auxiliary PID1.

Status_3_Quadrature 

Quadrature sensor.

Status_8_PulseWidth 

Pulse width sensor.

Status_11_UartGadgeteer 

Gadgeteer status.

Status_Brushless_Current 

Brushless Current Status.

Includes Stator and Supply Current for Talon FX.

Status_21_FeedbackIntegrated 

FX Integrated sensor.

◆ TalonFXControlMode

Choose the control mode for a TalonFX / Falcon 500.

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.

Enumerator
PercentOutput 

Percent output [-1,1].

Position 

Position closed loop.

Velocity 

Velocity closed loop.

Current 

Input current closed loop.

Follower 

Follow other motor controller.

MotionProfile 

Motion Profile.

MotionMagic 

Motion Magic.

MotionProfileArc 

Motion Profile with auxiliary output.

MusicTone 

Plays a single tone.

Frequency (hz) is passed into set.

Disabled 

Disable Motor Controller.

◆ TalonFXFeedbackDevice

Choose the feedback device for a Talon FX/Falcon 500.

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.

Enumerator
IntegratedSensor 

TalonFX supports an integrated sensor.

SensorSum 

Sum0 + Sum1.

SensorDifference 

Diff0 - Diff1.

RemoteSensor0 

Sensor configured in RemoteFilter0.

RemoteSensor1 

Sensor configured in RemoteFilter1.

None 

Position and velocity will read 0.

SoftwareEmulatedSensor 

Motor Controller will fake a sensor based on applied motor output.

◆ TalonFXInvertType

Choose the invert type for a Talon FX based integrated motor controller.

CCW is the equivalent of SetInverted(false), CW is the equivalent of SetInverted(true). FollowMaster/OpposeMaster will match/oppose a master Talon/Victor. This requires device to be configured as a follower.

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.

Enumerator
CounterClockwise 

Same as SetInverted(false)

Clockwise 

Same as SetInverted(true)

FollowMaster 

Follow the invert of the master this MC is following.

OpposeMaster 

Opposite of the invert of the master this MC is following.

◆ TalonSRXControlMode

Choose the control mode for a Talon SRX.

Enumerator
PercentOutput 

Percent output [-1,1].

Position 

Position closed loop.

Velocity 

Velocity closed loop.

Current 

Input current closed loop.

Follower 

Follow other motor controller.

MotionProfile 

Motion Profile.

MotionMagic 

Motion Magic.

MotionProfileArc 

Motion Profile with auxiliary output.

Disabled 

Disable Motor Controller.

◆ TalonSRXFeedbackDevice

Choose the feedback device for a Talon SRX.

Enumerator
QuadEncoder 

Quadrature encoder.

Analog 

Analog potentiometer/encoder.

Tachometer 

Tachometer.

PulseWidthEncodedPosition 

CTRE Mag Encoder in Absolute mode or any other device that uses PWM to encode its output.

SensorSum 

Sum0 + Sum1.

SensorDifference 

Diff0 - Diff1.

RemoteSensor0 

Sensor configured in RemoteFilter0.

RemoteSensor1 

Sensor configured in RemoteFilter1.

None 

Position and velocity will read 0.

SoftwareEmulatedSensor 

Motor Controller will fake a sensor based on applied motor output.

CTRE_MagEncoder_Absolute 

CTR mag encoder configured in absolute, is the same as a PWM sensor.

CTRE_MagEncoder_Relative 

CTR mag encoder configured in relative, is the same as an quadrature encoder sensor.

◆ VelocityMeasPeriod

Velocity Measurement Periods.

Enumerator
Period_1Ms 

1ms measurement period

Period_2Ms 

2ms measurement period

Period_5Ms 

5ms measurement period

Period_10Ms 

10ms measurement period

Period_20Ms 

20ms measurement period

Period_25Ms 

25ms measurement period

Period_50Ms 

50ms measurement period

Period_100Ms 

100ms measurement period

◆ VictorSPXControlMode

Choose the control mode for a Victor SPX.

Enumerator
PercentOutput 

Percent output [-1,1].

Position 

Position closed loop.

Velocity 

Velocity closed loop.

Follower 

Follow other motor controller.

MotionProfile 

Motion Profile.

MotionMagic 

Motion Magic.

MotionProfileArc 

Motion Profile with auxiliary output.

Disabled 

Disable Motor Controller.