2#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
4#pragma warning (disable : 4250)
7#include "ctre/phoenix/motorcontrol/can/BaseMotorController.h"
8#include "ctre/phoenix/motorcontrol/IMotorControllerEnhanced.h"
9#include "ctre/phoenix/motorcontrol/SupplyCurrentLimitConfiguration.h"
10#include "ctre/phoenix/CustomParamConfiguration.h"
11#include "ctre/phoenix/motorcontrol/SensorCollection.h"
12#include "ctre/phoenix/motorcontrol/TalonFXSensorCollection.h"
13#include "ctre/phoenix/motorcontrol/TalonSRXSimCollection.h"
14#include "ctre/phoenix/motorcontrol/TalonFXSimCollection.h"
19 namespace motorcontrol {
20 class SensorCollection;
27 namespace motorcontrol {
62 std::string
toString(std::string prependString) {
244 static bool ForwardLimitSwitchDeviceIDDifferent(
const BaseTalonConfiguration& settings) {
return (!(settings.forwardLimitSwitchDeviceID == _default.
forwardLimitSwitchDeviceID)) || !settings.enableOptimizations; }
245 static bool ReverseLimitSwitchDeviceIDDifferent(
const BaseTalonConfiguration& settings) {
return (!(settings.reverseLimitSwitchDeviceID == _default.
reverseLimitSwitchDeviceID)) || !settings.enableOptimizations; }
246 static bool ForwardLimitSwitchNormalDifferent(
const BaseTalonConfiguration& settings) {
return (!(settings.forwardLimitSwitchNormal == _default.
forwardLimitSwitchNormal)) || !settings.enableOptimizations; }
247 static bool ReverseLimitSwitchNormalDifferent(
const BaseTalonConfiguration& settings) {
return (!(settings.reverseLimitSwitchNormal == _default.
reverseLimitSwitchNormal)) || !settings.enableOptimizations; }
248 static bool Sum0TermDifferent(
const BaseTalonConfiguration& settings) { (void) settings;
return true; }
249 static bool Sum1TermDifferent(
const BaseTalonConfiguration& settings) { (void) settings;
return true; }
250 static bool Diff0TermDifferent(
const BaseTalonConfiguration& settings) { (void) settings;
return true; }
251 static bool Diff1TermDifferent(
const BaseTalonConfiguration& settings) { (void) settings;
return true; }
253 static bool ForwardLimitSwitchDifferent(
const BaseTalonConfiguration& settings) {
256 static bool ReverseLimitSwitchDifferent(
const BaseTalonConfiguration& settings) {
257 return ReverseLimitSwitchDeviceIDDifferent(settings) || ReverseLimitSwitchNormalDifferent(settings) || ReverseLimitSwitchSourceDifferent(settings);
325 BaseTalon(
int deviceNumber,
const char* model, std::string
const &canbus =
"");
473 [[deprecated(
"Use the overload with SensorVelocityMeasPeriod instead.")]]
625#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
static std::string toString(FeedbackDevice value)
Definition: FeedbackDevice.h:250
Definition: IMotorControllerEnhanced.h:28
static std::string toString(LimitSwitchSource value)
Definition: LimitSwitchType.h:109
Definition: SensorCollection.h:30
Definition: TalonFXSensorCollection.h:30
Definition: TalonFXSimCollection.h:25
Definition: TalonSRXSimCollection.h:25
Definition: BaseMotorController.h:577
Definition: BaseTalon.h:229
static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:242
Definition: BaseTalon.h:266
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs=0)
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(RemoteLimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
virtual double GetOutputCurrent()
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
int IsFwdLimitSwitchClosed()
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs=0)
int IsRevLimitSwitchClosed()
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs=0)
virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs=0)
virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration &currLimitConfigs, int timeoutMs=50)
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(RemoteLimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs=0)
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(ctre::phoenix::sensors::SensorVelocityMeasPeriod period, int timeoutMs=0)
void GetPIDConfigs(BaseTalonPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(LimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
ctre::phoenix::ErrorCode BaseTalonConfigAllSettings(const BaseTalonConfiguration &allConfigs, int timeoutMs=50)
void BaseTalonGetAllConfigs(BaseTalonConfiguration &allConfigs, int timeoutMs=50)
BaseTalon(int deviceNumber, const char *model, std::string const &canbus="")
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(LimitSwitchSource limitSwitchSource, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
double GetSupplyCurrent()
double GetStatorCurrent()
StatusFrameEnhanced
Definition: StatusFrame.h:10
LimitSwitchNormal
Definition: LimitSwitchType.h:61
@ LimitSwitchNormal_NormallyOpen
Definition: LimitSwitchType.h:66
RemoteFeedbackDevice
Definition: FeedbackDevice.h:169
RemoteLimitSwitchSource
Definition: LimitSwitchType.h:34
FeedbackDevice
Definition: FeedbackDevice.h:13
VelocityMeasPeriod
Definition: VelocityMeasPeriod.h:12
StatusFrame
Definition: StatusFrame.h:94
LimitSwitchSource
Definition: LimitSwitchType.h:10
@ LimitSwitchSource_FeedbackConnector
Definition: LimitSwitchType.h:14
SensorVelocityMeasPeriod
Definition: SensorVelocityMeasPeriod.h:12
ErrorCode
Definition: ErrorCode.h:12
Definition: ErrorCode.h:5
bool enableOptimizations
Definition: CustomParamConfiguration.h:22
Definition: SupplyCurrentLimitConfiguration.h:13
Definition: BaseMotorController.h:275
std::string toString()
Definition: BaseMotorController.h:473
Definition: BaseMotorController.h:49
double selectedFeedbackCoefficient
Definition: BaseMotorController.h:54
std::string toString()
Definition: BaseMotorController.h:64
Definition: BaseTalon.h:95
LimitSwitchSource reverseLimitSwitchSource
Definition: BaseTalon.h:115
FeedbackDevice sum0Term
Definition: BaseTalon.h:145
int reverseLimitSwitchDeviceID
Definition: BaseTalon.h:127
std::string toString()
Definition: BaseTalon.h:196
std::string toString(std::string prependString)
Definition: BaseTalon.h:205
FeedbackDevice diff1Term
Definition: BaseTalon.h:175
LimitSwitchSource forwardLimitSwitchSource
Definition: BaseTalon.h:109
int forwardLimitSwitchDeviceID
Definition: BaseTalon.h:121
LimitSwitchNormal forwardLimitSwitchNormal
Definition: BaseTalon.h:131
LimitSwitchNormal reverseLimitSwitchNormal
Definition: BaseTalon.h:135
FeedbackDevice sum1Term
Definition: BaseTalon.h:155
BaseTalonPIDSetConfiguration auxiliaryPID
Definition: BaseTalon.h:103
FeedbackDevice diff0Term
Definition: BaseTalon.h:165
BaseTalonPIDSetConfiguration primaryPID
Definition: BaseTalon.h:99
Definition: BaseTalon.h:73
static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration &settings)
Definition: BaseTalon.h:86
Definition: BaseTalon.h:33
FeedbackDevice selectedFeedbackSensor
Definition: BaseTalon.h:43
std::string toString()
Definition: BaseTalon.h:53
std::string toString(std::string prependString)
Definition: BaseTalon.h:62