CTRE_Phoenix 5.20.2
BaseTalon.h
1#pragma once
2#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
3#pragma warning (push)
4#pragma warning (disable : 4250)
5#endif
6
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"
15
16/* forward proto's */
17namespace ctre {
18 namespace phoenix {
19 namespace motorcontrol {
20 class SensorCollection;
21 }
22 }
23}
24
25namespace ctre {
26 namespace phoenix {
27 namespace motorcontrol {
28 namespace can {
29
44
45 BaseTalonPIDSetConfiguration(FeedbackDevice defaultFeedbackDevice) :
46 selectedFeedbackSensor(defaultFeedbackDevice)
47 {
48 }
49
53 std::string toString() {
54 return toString("");
55 }
56
62 std::string toString(std::string prependString) {
63
64 std::string retstr = prependString + ".selectedFeedbackSensor = " + FeedbackDeviceRoutines::toString(selectedFeedbackSensor) + ";\n";
65 retstr += BasePIDSetConfiguration::toString(prependString);
66 return retstr;
67 }
68 };
69
74 private:
75 static BaseTalonPIDSetConfiguration _default;
76 public:
77 /* Default feedback sensor is product specific. In order to ensure user always gets what they expect when selecting feedback sensor,
78 SelectedFeedbackSensorDifferent will always return true */
79
86 static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.selectedFeedbackSensor == _default.selectedFeedbackSensor)); }
87 static bool SelectedFeedbackCoefficientDifferent(const BaseTalonPIDSetConfiguration& settings) { return (!(settings.selectedFeedbackCoefficient == _default.selectedFeedbackCoefficient)); }
89 };
90
91
176
177 BaseTalonConfiguration(FeedbackDevice defaultFeedbackDevice) :
178 primaryPID(defaultFeedbackDevice),
179 auxiliaryPID(defaultFeedbackDevice),
186 sum0Term(defaultFeedbackDevice),
187 sum1Term(defaultFeedbackDevice),
188 diff0Term(defaultFeedbackDevice),
189 diff1Term(defaultFeedbackDevice)
190 {
191 }
192
196 std::string toString() {
197 return toString("");
198 }
199
205 std::string toString(std::string prependString) {
206
207
208 std::string retstr = primaryPID.toString(prependString + ".primaryPID");
209 retstr += auxiliaryPID.toString(prependString + ".auxiliaryPID");
210 retstr += prependString + ".forwardLimitSwitchSource = " + LimitSwitchRoutines::toString(forwardLimitSwitchSource) + ";\n";
211 retstr += prependString + ".reverseLimitSwitchSource = " + LimitSwitchRoutines::toString(reverseLimitSwitchSource) + ";\n";
212 retstr += prependString + ".forwardLimitSwitchDeviceID = " + std::to_string(forwardLimitSwitchDeviceID) + ";\n";
213 retstr += prependString + ".reverseLimitSwitchDeviceID = " + std::to_string(reverseLimitSwitchDeviceID) + ";\n";
214 retstr += prependString + ".forwardLimitSwitchNormal = " + LimitSwitchRoutines::toString(forwardLimitSwitchNormal) + ";\n";
215 retstr += prependString + ".reverseLimitSwitchNormal = " + LimitSwitchRoutines::toString(reverseLimitSwitchNormal) + ";\n";
216 retstr += prependString + ".sum0Term = " + FeedbackDeviceRoutines::toString(sum0Term) + ";\n";
217 retstr += prependString + ".sum1Term = " + FeedbackDeviceRoutines::toString(sum1Term) + ";\n";
218 retstr += prependString + ".diff0Term = " + FeedbackDeviceRoutines::toString(diff0Term) + ";\n";
219 retstr += prependString + ".diff1Term = " + FeedbackDeviceRoutines::toString(diff1Term) + ";\n";
220 retstr += BaseMotorControllerConfiguration::toString(prependString);
221
222 return retstr;
223 }
224 };// struct BaseTalonConfiguration
225
230 private:
231 static struct BaseTalonConfiguration _default;
232 public:
233 /* Default feedback sensor is product specific. In order to ensure user always gets what they expect when selecting feedback sensor,
234 (Sum/Diff)(0/1)TermDifferent will always return true */
235
242 static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration& settings) { return (!(settings.forwardLimitSwitchSource == _default.forwardLimitSwitchSource)) || !settings.enableOptimizations; }
243 static bool ReverseLimitSwitchSourceDifferent(const BaseTalonConfiguration& settings) { return (!(settings.reverseLimitSwitchSource == _default.reverseLimitSwitchSource)) || !settings.enableOptimizations; }
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; } //{ return (!(settings.sum0Term == _default.sum0Term)) || !settings.enableOptimizations; }
249 static bool Sum1TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.sum1Term == _default.sum1Term)) || !settings.enableOptimizations; }
250 static bool Diff0TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.diff0Term == _default.diff0Term)) || !settings.enableOptimizations; }
251 static bool Diff1TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.diff1Term == _default.diff1Term)) || !settings.enableOptimizations; }
252
253 static bool ForwardLimitSwitchDifferent(const BaseTalonConfiguration& settings) {
254 return ForwardLimitSwitchDeviceIDDifferent(settings) || ForwardLimitSwitchNormalDifferent(settings) || ForwardLimitSwitchSourceDifferent(settings);
255 }
256 static bool ReverseLimitSwitchDifferent(const BaseTalonConfiguration& settings) {
257 return ReverseLimitSwitchDeviceIDDifferent(settings) || ReverseLimitSwitchNormalDifferent(settings) || ReverseLimitSwitchSourceDifferent(settings);
258 }
260 };
261
265 class BaseTalon : public virtual BaseMotorController, public virtual IMotorControllerEnhanced
266 {
267 private:
270
273
274 protected:
275 ctre::phoenix::motorcontrol::SensorCollection& GetTalonSRXSensorCollection() { return *_sensorCollSrx; }
276 ctre::phoenix::motorcontrol::TalonFXSensorCollection& GetTalonFXSensorCollection() { return *_sensorCollFx; }
277
278 ctre::phoenix::motorcontrol::TalonSRXSimCollection& GetTalonSRXSimCollection() { return *_simCollSrx; }
279 ctre::phoenix::motorcontrol::TalonFXSimCollection& GetTalonFXSimCollection() { return *_simCollFx; }
280
281 ctre::phoenix::ErrorCode ConfigurePID(const BaseTalonPIDSetConfiguration& pid, int pidIdx, int timeoutMs, bool enableOptimizations);
282
283
284 //------ All Configs ----------//
295 void GetPIDConfigs(BaseTalonPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
317 void BaseTalonGetAllConfigs(BaseTalonConfiguration& allConfigs, int timeoutMs = 50);
318 public:
325 BaseTalon(int deviceNumber, const char* model, std::string const &canbus = "");
326 virtual ~BaseTalon();
327 BaseTalon() = delete;
328 BaseTalon(BaseTalon const&) = delete;
329 BaseTalon& operator=(BaseTalon const&) = delete;
330
345 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
360 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
361
381 virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs = 0);
401 virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs = 0);
402
414 virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs = 0);
426 virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs = 0);
427
428 //------ General Status ----------//
438 virtual double GetOutputCurrent();
439
446
453
454 //------ Velocity measurement ----------//
471 int timeoutMs = 0);
472
473 [[deprecated("Use the overload with SensorVelocityMeasPeriod instead.")]]
475 int timeoutMs = 0);
491 int timeoutMs = 0);
492
493 //------ limit switch ----------//
516 LimitSwitchSource limitSwitchSource,
517 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
542 RemoteLimitSwitchSource limitSwitchSource,
543 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs = 0);
567 LimitSwitchSource limitSwitchSource,
568 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
594 RemoteLimitSwitchSource limitSwitchSource,
595 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs = 0);
596
597 //------ Current Limit ----------//
598 virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration& currLimitConfigs, int timeoutMs = 50);
599
600 //------ RAW Sensor API ----------//
609
618 };// class BaseTalon
619
620 } // namespace can
621 } // namespace motorcontrol
622 } // namespace phoenix
623} // namespace ctre
624
625#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
626#pragma warning (pop)
627#endif
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
static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Definition: BaseTalon.h:242
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 ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs=0)
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)
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
std::string toString()
Definition: BaseMotorController.h:473
double selectedFeedbackCoefficient
Definition: BaseMotorController.h:54
std::string toString()
Definition: BaseMotorController.h:64
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
static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration &settings)
Definition: BaseTalon.h:86
FeedbackDevice selectedFeedbackSensor
Definition: BaseTalon.h:43
std::string toString()
Definition: BaseTalon.h:53
std::string toString(std::string prependString)
Definition: BaseTalon.h:62