3#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
5#pragma warning (disable : 4250)
20 namespace motorcontrol {
21 class SensorCollection;
28 namespace motorcontrol {
63 std::string
toString(std::string prependString) {
276 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
277 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
278 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
280 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
281 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
282 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
285 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
286 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
287 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
289 [[deprecated(
"This device's Phoenix 5 API is deprecated for removal in the 2025 season."
290 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
291 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
338 BaseTalon(
int deviceNumber,
const char* model, std::string
const &canbus =
"");
486 [[deprecated(
"Use the overload with SensorVelocityMeasPeriod instead.")]]
638#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
static std::string toString(FeedbackDevice value)
Gets the string representation of selected feedback device.
Definition: FeedbackDevice.h:260
Interface for enhanced motor controllers.
Definition: IMotorControllerEnhanced.h:29
static std::string toString(LimitSwitchSource value)
Definition: LimitSwitchType.h:110
Collection of sensors available to a motor controller.
Definition: SensorCollection.h:31
Collection of sensors available to the Talon FX.
Definition: TalonFXSensorCollection.h:40
Collection of simulation commands available to a TalonFX motor controller.
Definition: TalonFXSimCollection.h:35
Collection of simulation commands available to a TalonSRX motor controller.
Definition: TalonSRXSimCollection.h:26
Base motor controller features for all CTRE CAN motor controllers.
Definition: BaseMotorController.h:578
Util class to help with talon configs.
Definition: BaseTalon.h:230
static bool Sum0TermDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:249
static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseTalon.h:243
static bool Diff0TermDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:251
static bool ReverseLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:246
static bool ReverseLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:244
static bool Diff1TermDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:252
static bool ForwardLimitSwitchDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:254
static bool ReverseLimitSwitchNormalDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:248
static bool Sum1TermDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:250
static bool ForwardLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:245
static bool ForwardLimitSwitchNormalDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:247
static bool ReverseLimitSwitchDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:257
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: BaseTalon.h:267
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(RemoteLimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures a limit switch for a local/remote source.
virtual double GetOutputCurrent()
Gets the output current of the motor controller.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
ctre::phoenix::motorcontrol::TalonFXSimCollection & GetTalonFXSimCollection()
Definition: BaseTalon.h:292
ctre::phoenix::motorcontrol::TalonFXSensorCollection & GetTalonFXSensorCollection()
Definition: BaseTalon.h:283
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs=0)
Sets the period over which velocity measurements are taken.
int IsFwdLimitSwitchClosed()
Is forward limit switch closed.
BaseTalon(BaseTalon const &)=delete
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs=0)
Gets the period of the given status frame.
int IsRevLimitSwitchClosed()
Is reverse limit switch closed.
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration &currLimitConfigs, int timeoutMs=50)
Configures the supply-side current limit.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(RemoteLimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures a limit switch for a local/remote source.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs=0)
Sets the number of velocity samples used in the rolling average velocity measurement.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(ctre::phoenix::sensors::SensorVelocityMeasPeriod period, int timeoutMs=0)
Configures the period of each velocity sample.
ctre::phoenix::motorcontrol::SensorCollection & GetTalonSRXSensorCollection()
Definition: BaseTalon.h:279
ctre::phoenix::ErrorCode ConfigurePID(const BaseTalonPIDSetConfiguration &pid, int pidIdx, int timeoutMs, bool enableOptimizations)
void GetPIDConfigs(BaseTalonPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
Gets all PID set persistant settings.
BaseTalon & operator=(BaseTalon const &)=delete
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(LimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
ctre::phoenix::ErrorCode BaseTalonConfigAllSettings(const BaseTalonConfiguration &allConfigs, int timeoutMs=50)
Configures all persistent settings.
void BaseTalonGetAllConfigs(BaseTalonConfiguration &allConfigs, int timeoutMs=50)
Gets all persistant settings.
ctre::phoenix::motorcontrol::TalonSRXSimCollection & GetTalonSRXSimCollection()
Definition: BaseTalon.h:288
BaseTalon(int deviceNumber, const char *model, std::string const &canbus="")
Constructor for a Talon.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(LimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
double GetSupplyCurrent()
Gets the supply/input current of the motor controller.
double GetStatorCurrent()
Gets the stator/output current of the motor controller.
StatusFrameEnhanced
The different status frames available to enhanced motor controllers.
Definition: StatusFrame.h:11
LimitSwitchNormal
Choose whether the limit switch is normally open or normally closed.
Definition: LimitSwitchType.h:62
@ LimitSwitchNormal_NormallyOpen
Limit Switch is tripped when the circuit is closed.
Definition: LimitSwitchType.h:67
RemoteFeedbackDevice
Choose the remote feedback device for a motor controller.
Definition: FeedbackDevice.h:179
RemoteLimitSwitchSource
Remote Limit switch source enum.
Definition: LimitSwitchType.h:35
FeedbackDevice
Choose the feedback device for a motor controller.
Definition: FeedbackDevice.h:14
VelocityMeasPeriod
Velocity Measurement Periods.
Definition: VelocityMeasPeriod.h:13
StatusFrame
The different status frames available to motor controllers.
Definition: StatusFrame.h:99
LimitSwitchSource
Limit switch source enum.
Definition: LimitSwitchType.h:11
@ LimitSwitchSource_FeedbackConnector
Limit switch directly connected to motor controller.
Definition: LimitSwitchType.h:15
SensorVelocityMeasPeriod
Enumerate filter periods for any sensor that measures velocity.
Definition: SensorVelocityMeasPeriod.h:13
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
Describes the desired stator current limiting behavior.
Definition: SupplyCurrentLimitConfiguration.h:13
Configurables available to base motor controllers.
Definition: BaseMotorController.h:276
std::string toString()
Definition: BaseMotorController.h:474
Base set of configurables related to PID.
Definition: BaseMotorController.h:50
double selectedFeedbackCoefficient
Feedback coefficient of selected sensor.
Definition: BaseMotorController.h:55
std::string toString()
Definition: BaseMotorController.h:65
Configurables available to BaseTalon.
Definition: BaseTalon.h:96
LimitSwitchSource reverseLimitSwitchSource
Reverse Limit Switch Source.
Definition: BaseTalon.h:116
FeedbackDevice sum0Term
Feedback Device for Sum 0 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition: BaseTalon.h:146
int reverseLimitSwitchDeviceID
Reverse limit switch device ID.
Definition: BaseTalon.h:128
std::string toString()
Definition: BaseTalon.h:197
std::string toString(std::string prependString)
Definition: BaseTalon.h:206
FeedbackDevice diff1Term
Feedback Device for Diff 1 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition: BaseTalon.h:176
LimitSwitchSource forwardLimitSwitchSource
Forward Limit Switch Source.
Definition: BaseTalon.h:110
int forwardLimitSwitchDeviceID
Forward limit switch device ID.
Definition: BaseTalon.h:122
BaseTalonConfiguration(FeedbackDevice defaultFeedbackDevice)
Definition: BaseTalon.h:178
LimitSwitchNormal forwardLimitSwitchNormal
Forward limit switch normally open/closed.
Definition: BaseTalon.h:132
LimitSwitchNormal reverseLimitSwitchNormal
Reverse limit switch normally open/closed.
Definition: BaseTalon.h:136
FeedbackDevice sum1Term
Feedback Device for Sum 1 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition: BaseTalon.h:156
BaseTalonPIDSetConfiguration auxiliaryPID
Auxiliary PID configuration.
Definition: BaseTalon.h:104
FeedbackDevice diff0Term
Feedback Device for Diff 0 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition: BaseTalon.h:166
BaseTalonPIDSetConfiguration primaryPID
Primary PID configuration.
Definition: BaseTalon.h:100
Util class to help with BaseTalon's PID configs.
Definition: BaseTalon.h:74
static bool SelectedFeedbackCoefficientDifferent(const BaseTalonPIDSetConfiguration &settings)
Definition: BaseTalon.h:88
static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseTalon.h:87
Configurables available to BaseTalon's PID.
Definition: BaseTalon.h:34
FeedbackDevice selectedFeedbackSensor
Feedback device for a particular PID loop.
Definition: BaseTalon.h:44
std::string toString()
Definition: BaseTalon.h:54
BaseTalonPIDSetConfiguration(FeedbackDevice defaultFeedbackDevice)
Definition: BaseTalon.h:46
std::string toString(std::string prependString)
Definition: BaseTalon.h:63