CTRE Phoenix C++ 5.35.1
Loading...
Searching...
No Matches
BaseTalon.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2#pragma once
3#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
4#pragma warning (push)
5#pragma warning (disable : 4250)
6#endif
7
14
15/* forward proto's */
16namespace ctre {
17 namespace phoenix {
18 namespace motorcontrol {
19 class SensorCollection;
20 }
21 }
22}
23
24namespace ctre {
25 namespace phoenix {
26 namespace motorcontrol {
27 namespace can {
28
29 /**
30 * Configurables available to BaseTalon's PID
31 */
33 /**
34 * Feedback device for a particular PID loop.
35 * Note the FeedbackDevice enum holds all possible sensor types. Consult product documentation to confirm what is available.
36 * Alternatively the product specific enum can be used instead.
37 * @code
38 * configs.primaryPID.selectedFeedbackSensor = (FeedbackDevice)TalonSRXFeedbackDevice::QuadEncoder;
39 * @endcode
40 */
42
44 selectedFeedbackSensor(defaultFeedbackDevice)
45 {
46 }
47
48 /**
49 * @return string representation of configs
50 */
51 std::string toString() {
52 return toString("");
53 }
54
55 /**
56 * @param prependString
57 * String to prepend to configs
58 * @return String representation of configs
59 */
60 std::string toString(std::string prependString) {
61
62 std::string retstr = prependString + ".selectedFeedbackSensor = " + FeedbackDeviceRoutines::toString(selectedFeedbackSensor) + ";\n";
63 retstr += BasePIDSetConfiguration::toString(prependString);
64 return retstr;
65 }
66 };
67
68 /**
69 * Util class to help with BaseTalon's PID configs
70 */
72 private:
73 static const BaseTalonPIDSetConfiguration &_default();
74 public:
75 /* Default feedback sensor is product specific. In order to ensure user always gets what they expect when selecting feedback sensor,
76 SelectedFeedbackSensorDifferent will always return true */
77
78 /**
79 * Determine if specified value is different from default
80 * @param settings settings to compare against
81 * @return if specified value is different from default
82 * @{
83 */
84 static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.selectedFeedbackSensor == _default().selectedFeedbackSensor)); }
85 static bool SelectedFeedbackCoefficientDifferent(const BaseTalonPIDSetConfiguration& settings) { return (!(settings.selectedFeedbackCoefficient == _default().selectedFeedbackCoefficient)); }
86 /** @} */
87 };
88
89
90 /**
91 * Configurables available to BaseTalon
92 */
94 /**
95 * Primary PID configuration
96 */
98 /**
99 * Auxiliary PID configuration
100 */
102 /**
103 * Forward Limit Switch Source
104 *
105 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature
106 */
108 /**
109 * Reverse Limit Switch Source
110 *
111 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature
112 */
114 /**
115 * Forward limit switch device ID
116 *
117 * Limit Switch device id isn't used unless device is a remote
118 */
120 /**
121 * Reverse limit switch device ID
122 *
123 * Limit Switch device id isn't used unless device is a remote
124 */
126 /**
127 * Forward limit switch normally open/closed
128 */
130 /**
131 * Reverse limit switch normally open/closed
132 */
134 /**
135 * Feedback Device for Sum 0 Term
136 * Note the FeedbackDevice enum holds all possible sensor types. Consult product documentation to confirm what is available.
137 * Alternatively the product specific enum can be used instead.
138 * @code
139 * configs.sum0Term = (FeedbackDevice)TalonSRXFeedbackDevice::QuadEncoder;
140 * @endcode
141 */
143 /**
144 * Feedback Device for Sum 1 Term
145 * Note the FeedbackDevice enum holds all possible sensor types. Consult product documentation to confirm what is available.
146 * Alternatively the product specific enum can be used instead.
147 * @code
148 * configs.sum1Term = (FeedbackDevice)TalonSRXFeedbackDevice::QuadEncoder;
149 * @endcode
150 */
152 /**
153 * Feedback Device for Diff 0 Term
154 * Note the FeedbackDevice enum holds all possible sensor types. Consult product documentation to confirm what is available.
155 * Alternatively the product specific enum can be used instead.
156 * @code
157 * configs.diff0Term = (FeedbackDevice)TalonSRXFeedbackDevice::QuadEncoder;
158 * @endcode
159 */
161 /**
162 * Feedback Device for Diff 1 Term
163 * Note the FeedbackDevice enum holds all possible sensor types. Consult product documentation to confirm what is available.
164 * Alternatively the product specific enum can be used instead.
165 * @code
166 * configs.diff1Term = (FeedbackDevice)TalonSRXFeedbackDevice::QuadEncoder;
167 * @endcode
168 */
170
171 BaseTalonConfiguration(FeedbackDevice defaultFeedbackDevice) :
172 primaryPID(defaultFeedbackDevice),
173 auxiliaryPID(defaultFeedbackDevice),
180 sum0Term(defaultFeedbackDevice),
181 sum1Term(defaultFeedbackDevice),
182 diff0Term(defaultFeedbackDevice),
183 diff1Term(defaultFeedbackDevice)
184 {
185 }
186
187 /**
188 * @return String representation of all the configs
189 */
190 std::string toString() {
191 return toString("");
192 }
193
194 /**
195 * @param prependString
196 * String to prepend to all the configs
197 * @return String representation of all the configs
198 */
199 std::string toString(std::string prependString) {
200
201
202 std::string retstr = primaryPID.toString(prependString + ".primaryPID");
203 retstr += auxiliaryPID.toString(prependString + ".auxiliaryPID");
204 retstr += prependString + ".forwardLimitSwitchSource = " + LimitSwitchRoutines::toString(forwardLimitSwitchSource) + ";\n";
205 retstr += prependString + ".reverseLimitSwitchSource = " + LimitSwitchRoutines::toString(reverseLimitSwitchSource) + ";\n";
206 retstr += prependString + ".forwardLimitSwitchDeviceID = " + std::to_string(forwardLimitSwitchDeviceID) + ";\n";
207 retstr += prependString + ".reverseLimitSwitchDeviceID = " + std::to_string(reverseLimitSwitchDeviceID) + ";\n";
208 retstr += prependString + ".forwardLimitSwitchNormal = " + LimitSwitchRoutines::toString(forwardLimitSwitchNormal) + ";\n";
209 retstr += prependString + ".reverseLimitSwitchNormal = " + LimitSwitchRoutines::toString(reverseLimitSwitchNormal) + ";\n";
210 retstr += prependString + ".sum0Term = " + FeedbackDeviceRoutines::toString(sum0Term) + ";\n";
211 retstr += prependString + ".sum1Term = " + FeedbackDeviceRoutines::toString(sum1Term) + ";\n";
212 retstr += prependString + ".diff0Term = " + FeedbackDeviceRoutines::toString(diff0Term) + ";\n";
213 retstr += prependString + ".diff1Term = " + FeedbackDeviceRoutines::toString(diff1Term) + ";\n";
214 retstr += BaseMotorControllerConfiguration::toString(prependString);
215
216 return retstr;
217 }
218 };// struct BaseTalonConfiguration
219
220 /**
221 * Util class to help with talon configs
222 */
224 private:
225 static const struct BaseTalonConfiguration &_default();
226 public:
227 /* Default feedback sensor is product specific. In order to ensure user always gets what they expect when selecting feedback sensor,
228 (Sum/Diff)(0/1)TermDifferent will always return true */
229
230 /**
231 * Determine if specified value is different from default
232 * @param settings settings to compare against
233 * @return if specified value is different from default
234 * @{
235 */
236 static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration& settings) { return (!(settings.forwardLimitSwitchSource == _default().forwardLimitSwitchSource)) || !settings.enableOptimizations; }
237 static bool ReverseLimitSwitchSourceDifferent(const BaseTalonConfiguration& settings) { return (!(settings.reverseLimitSwitchSource == _default().reverseLimitSwitchSource)) || !settings.enableOptimizations; }
238 static bool ForwardLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration& settings) { return (!(settings.forwardLimitSwitchDeviceID == _default().forwardLimitSwitchDeviceID)) || !settings.enableOptimizations; }
239 static bool ReverseLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration& settings) { return (!(settings.reverseLimitSwitchDeviceID == _default().reverseLimitSwitchDeviceID)) || !settings.enableOptimizations; }
240 static bool ForwardLimitSwitchNormalDifferent(const BaseTalonConfiguration& settings) { return (!(settings.forwardLimitSwitchNormal == _default().forwardLimitSwitchNormal)) || !settings.enableOptimizations; }
241 static bool ReverseLimitSwitchNormalDifferent(const BaseTalonConfiguration& settings) { return (!(settings.reverseLimitSwitchNormal == _default().reverseLimitSwitchNormal)) || !settings.enableOptimizations; }
242 static bool Sum0TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.sum0Term == _default().sum0Term)) || !settings.enableOptimizations; }
243 static bool Sum1TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.sum1Term == _default().sum1Term)) || !settings.enableOptimizations; }
244 static bool Diff0TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.diff0Term == _default().diff0Term)) || !settings.enableOptimizations; }
245 static bool Diff1TermDifferent(const BaseTalonConfiguration& settings) { (void) settings; return true; } //{ return (!(settings.diff1Term == _default().diff1Term)) || !settings.enableOptimizations; }
246
253 /** @} */
254 };
255
256 /**
257 * CTRE Talon SRX Motor Controller when used on CAN Bus.
258 */
259 class BaseTalon : public virtual BaseMotorController, public virtual IMotorControllerEnhanced
260 {
261 private:
263
265
266 protected:
269
270 ctre::phoenix::ErrorCode ConfigurePID(const BaseTalonPIDSetConfiguration& pid, int pidIdx, int timeoutMs, bool enableOptimizations);
271
272
273 //------ All Configs ----------//
274 /**
275 * Gets all PID set persistant settings.
276 *
277 * @param pid Object with all of the PID set persistant settings
278 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
279 * @param timeoutMs
280 * Timeout value in ms. If nonzero, function will wait for
281 * config success and report an error if it times out.
282 * If zero, no blocking or checking is performed.
283 */
284 void GetPIDConfigs(BaseTalonPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
285 /**
286 * Configures all persistent settings.
287 *
288 * @param allConfigs Object with all of the persistant settings
289 * @param timeoutMs
290 * Timeout value in ms. If nonzero, function will wait for
291 * config success and report an error if it times out.
292 * If zero, no blocking or checking is performed.
293 *
294 * @return Error Code generated by function. 0 indicates no error.
295 */
297 /**
298 * Gets all persistant settings.
299 *
300 * @param allConfigs Object with all of the persistant settings
301 * @param timeoutMs
302 * Timeout value in ms. If nonzero, function will wait for
303 * config success and report an error if it times out.
304 * If zero, no blocking or checking is performed.
305 */
306 void BaseTalonGetAllConfigs(BaseTalonConfiguration& allConfigs, int timeoutMs = 50);
307 public:
308 /**
309 * Constructor for a Talon
310 * @param deviceNumber CAN Device ID of BaseTalon
311 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
312 * or a CANivore device name or serial number
313 */
314 BaseTalon(int deviceNumber, const char* model, std::string const &canbus = "");
315 virtual ~BaseTalon();
316 BaseTalon() = delete;
317 BaseTalon(BaseTalon const&) = delete;
318 BaseTalon& operator=(BaseTalon const&) = delete;
319
320 /**
321 * Select the remote feedback device for the motor controller.
322 * Most CTRE CAN motor controllers will support remote sensors over CAN.
323 *
324 * @param feedbackDevice
325 * Remote Feedback Device to select.
326 * @param pidIdx
327 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
328 * @param timeoutMs
329 * Timeout value in ms. If nonzero, function will wait for
330 * config success and report an error if it times out.
331 * If zero, no blocking or checking is performed.
332 * @return Error Code generated by function. 0 indicates no error.
333 */
334 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
335 /**
336 * Select the remote feedback device for the motor controller.
337 * Most CTRE CAN motor controllers will support remote sensors over CAN.
338 *
339 * @param feedbackDevice
340 * Remote Feedback Device to select.
341 * @param pidIdx
342 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
343 * @param timeoutMs
344 * Timeout value in ms. If nonzero, function will wait for
345 * config success and report an error if it times out.
346 * If zero, no blocking or checking is performed.
347 * @return Error Code generated by function. 0 indicates no error.
348 */
349 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
350
351 /**
352 * Sets the period of the given status frame.
353 *
354 * User ensure CAN Bus utilization is not high.
355 *
356 * This setting is not persistent and is lost when device is reset.
357 * If this is a concern, calling application can use HasResetOccurred()
358 * to determine if the status frame needs to be reconfigured.
359 *
360 * @param frame
361 * Frame whose period is to be changed.
362 * @param periodMs
363 * Period in ms for the given frame.
364 * @param timeoutMs
365 * Timeout value in ms. If nonzero, function will wait for
366 * config success and report an error if it times out.
367 * If zero, no blocking or checking is performed.
368 * @return Error Code generated by function. 0 indicates no error.
369 */
370 virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs = 0);
371 /**
372 * Sets the period of the given status frame.
373 *
374 * User ensure CAN Bus utilization is not high.
375 *
376 * This setting is not persistent and is lost when device is reset.
377 * If this is a concern, calling application can use HasResetOccurred()
378 * to determine if the status frame needs to be reconfigured.
379 *
380 * @param frame
381 * Frame whose period is to be changed.
382 * @param periodMs
383 * Period in ms for the given frame.
384 * @param timeoutMs
385 * Timeout value in ms. If nonzero, function will wait for
386 * config success and report an error if it times out.
387 * If zero, no blocking or checking is performed.
388 * @return Error Code generated by function. 0 indicates no error.
389 */
390 virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs = 0);
391
392 /**
393 * Gets the period of the given status frame.
394 *
395 * @param frame
396 * Frame to get the period of.
397 * @param timeoutMs
398 * Timeout value in ms. If nonzero, function will wait for
399 * config success and report an error if it times out.
400 * If zero, no blocking or checking is performed.
401 * @return Period of the given status frame.
402 */
403 virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs = 0);
404 /**
405 * Gets the period of the given status frame.
406 *
407 * @param frame
408 * Frame to get the period of.
409 * @param timeoutMs
410 * Timeout value in ms. If nonzero, function will wait for
411 * config success and report an error if it times out.
412 * If zero, no blocking or checking is performed.
413 * @return Period of the given status frame.
414 */
415 virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs = 0);
416
417 //------ General Status ----------//
418 /**
419 * Gets the output current of the motor controller.
420 * In the case of TalonSRX class, this routine returns supply current for legacy reasons. In order to get the "true" output current, call GetStatorCurrent().
421 *
422 * [[deprecated("Use GetStatorCurrent/GetSupplyCurrent instead.")]]
423 *
424 * @return The output current (in amps).
425 */
426 virtual double GetOutputCurrent();
427
428 /**
429 * Gets the stator/output current of the motor controller.
430 *
431 * @return The stator/output current (in amps).
432 */
434
435 /**
436 * Gets the supply/input current of the motor controller.
437 *
438 * @return The supply/input current (in amps).
439 */
441
442 //------ Velocity measurement ----------//
443 /**
444 * Configures the period of each velocity sample.
445 * Every 1ms a position value is sampled, and the delta between that sample
446 * and the position sampled kPeriod ms ago is inserted into a filter.
447 * kPeriod is configured with this function.
448 *
449 * @param period
450 * Desired period for the velocity measurement. @see
451 * #SensorVelocityMeasPeriod
452 * @param timeoutMs
453 * Timeout value in ms. If nonzero, function will wait for
454 * config success and report an error if it times out.
455 * If zero, no blocking or checking is performed.
456 * @return Error Code generated by function. 0 indicates no error.
457 */
459 int timeoutMs = 0);
460
461 [[deprecated("Use the overload with SensorVelocityMeasPeriod instead.")]]
463 int timeoutMs = 0);
464 /**
465 * Sets the number of velocity samples used in the rolling average velocity
466 * measurement.
467 *
468 * @param windowSize
469 * Number of samples in the rolling average of velocity
470 * measurement. Valid values are 1,2,4,8,16,32. If another
471 * value is specified, it will truncate to nearest support value.
472 * @param timeoutMs
473 * Timeout value in ms. If nonzero, function will wait for
474 * config success and report an error if it times out.
475 * If zero, no blocking or checking is performed.
476 * @return Error Code generated by function. 0 indicates no error.
477 */
479 int timeoutMs = 0);
480
481 //------ limit switch ----------//
482 /**
483 * Configures a limit switch for a local/remote source.
484 *
485 * For example, a CAN motor controller may need to monitor the Limit-R pin
486 * of another Talon, CANifier, or local Gadgeteer feedback connector.
487 *
488 * If the sensor is remote, a device ID of zero is assumed.
489 * If that's not desired, use the four parameter version of this function.
490 *
491 * @param limitSwitchSource
492 * Limit switch source.
493 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
494 * @param normalOpenOrClose
495 * Setting for normally open, normally closed, or disabled. This setting
496 * matches the Phoenix Tuner drop down.
497 * @param timeoutMs
498 * Timeout value in ms. If nonzero, function will wait for
499 * config success and report an error if it times out.
500 * If zero, no blocking or checking is performed.
501 * @return Error Code generated by function. 0 indicates no error.
502 */
504 LimitSwitchSource limitSwitchSource,
505 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
506 /**
507 * Configures a limit switch for a local/remote source.
508 *
509 * For example, a CAN motor controller may need to monitor the Limit-R pin
510 * of another Talon, CANifier, or local Gadgeteer feedback connector.
511 *
512 * If the sensor is remote, a device ID of zero is assumed.
513 * If that's not desired, use the four parameter version of this function.
514 *
515 * @param limitSwitchSource
516 * Limit switch source.
517 * User can choose between the feedback connector, remote Talon SRX, CANifier, or deactivate the feature.
518 * @param normalOpenOrClose
519 * Setting for normally open, normally closed, or disabled. This setting
520 * matches the Phoenix Tuner drop down.
521 * @param deviceID
522 * Device ID of remote source (Talon SRX or CANifier device ID).
523 * @param timeoutMs
524 * Timeout value in ms. If nonzero, function will wait for
525 * config success and report an error if it times out.
526 * If zero, no blocking or checking is performed.
527 * @return Error Code generated by function. 0 indicates no error.
528 */
530 RemoteLimitSwitchSource limitSwitchSource,
531 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs = 0);
532 /**
533 * Configures a limit switch for a local/remote source.
534 *
535 * For example, a CAN motor controller may need to monitor the Limit-R pin
536 * of another Talon, CANifier, or local Gadgeteer feedback connector.
537 *
538 * If the sensor is remote, a device ID of zero is assumed. If that's not
539 * desired, use the four parameter version of this function.
540 *
541 * @param limitSwitchSource
542 * Limit switch source. @see #LimitSwitchSource User can choose
543 * between the feedback connector, remote Talon SRX, CANifier, or
544 * deactivate the feature.
545 * @param normalOpenOrClose
546 * Setting for normally open, normally closed, or disabled. This
547 * setting matches the Phoenix Tuner drop down.
548 * @param timeoutMs
549 * Timeout value in ms. If nonzero, function will wait for config
550 * success and report an error if it times out. If zero, no
551 * blocking or checking is performed.
552 * @return Error Code generated by function. 0 indicates no error.
553 */
555 LimitSwitchSource limitSwitchSource,
556 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
557 /**
558 * Configures a limit switch for a local/remote source.
559 *
560 * For example, a CAN motor controller may need to monitor the Limit-R pin
561 * of another Talon, CANifier, or local Gadgeteer feedback connector.
562 *
563 * If the sensor is remote, a device ID of zero is assumed. If that's not
564 * desired, use the four parameter version of this function.
565 *
566 * @param limitSwitchSource
567 * Limit switch source. @see #LimitSwitchSource User can choose
568 * between the feedback connector, remote Talon SRX, CANifier, or
569 * deactivate the feature.
570 * @param normalOpenOrClose
571 * Setting for normally open, normally closed, or disabled. This
572 * setting matches the Phoenix Tuner drop down.
573 * @param deviceID
574 * Device ID of remote source (Talon SRX or CANifier device ID).
575 * @param timeoutMs
576 * Timeout value in ms. If nonzero, function will wait for config
577 * success and report an error if it times out. If zero, no
578 * blocking or checking is performed.
579 * @return Error Code generated by function. 0 indicates no error.
580 */
582 RemoteLimitSwitchSource limitSwitchSource,
583 LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs = 0);
584
585 //------ Current Limit ----------//
586 virtual ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const SupplyCurrentLimitConfiguration& currLimitConfigs, int timeoutMs = 50);
587
588 //------ RAW Sensor API ----------//
589 /**
590 * Is forward limit switch closed.
591 *
592 * @return '1' iff forward limit switch is closed, 0 iff switch is open. This function works
593 * regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
594 */
595
597
598 /**
599 * Is reverse limit switch closed.
600 *
601 * @return '1' iff reverse limit switch is closed, 0 iff switch is open. This function works
602 * regardless if limit switch feature is enabled. Remote limit features do not impact this routine.
603 */
604
606 };// class BaseTalon
607
608 } // namespace can
609 } // namespace motorcontrol
610 } // namespace phoenix
611} // namespace ctre
612
613#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
614#pragma warning (pop)
615#endif
static std::string toString(FeedbackDevice value)
Gets the string representation of selected feedback device.
Definition FeedbackDevice.h:212
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 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:223
static bool Sum0TermDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:242
static bool ForwardLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Determine if specified value is different from default.
Definition BaseTalon.h:236
static bool Diff0TermDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:244
static bool ReverseLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:239
static bool ReverseLimitSwitchSourceDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:237
static bool Diff1TermDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:245
static bool ForwardLimitSwitchDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:247
static bool ReverseLimitSwitchNormalDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:241
static bool Sum1TermDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:243
static bool ForwardLimitSwitchDeviceIDDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:238
static bool ForwardLimitSwitchNormalDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:240
static bool ReverseLimitSwitchDifferent(const BaseTalonConfiguration &settings)
Definition BaseTalon.h:250
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition BaseTalon.h:260
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.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs=0)
int IsFwdLimitSwitchClosed()
Is forward limit switch closed.
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:267
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:268
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:131
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
WPI Compliant CANcoder class.
Definition CANCoderStatusFrame.h:4
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:93
LimitSwitchSource reverseLimitSwitchSource
Reverse Limit Switch Source.
Definition BaseTalon.h:113
FeedbackDevice sum0Term
Feedback Device for Sum 0 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition BaseTalon.h:142
int reverseLimitSwitchDeviceID
Reverse limit switch device ID.
Definition BaseTalon.h:125
std::string toString()
Definition BaseTalon.h:190
std::string toString(std::string prependString)
Definition BaseTalon.h:199
FeedbackDevice diff1Term
Feedback Device for Diff 1 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition BaseTalon.h:169
LimitSwitchSource forwardLimitSwitchSource
Forward Limit Switch Source.
Definition BaseTalon.h:107
int forwardLimitSwitchDeviceID
Forward limit switch device ID.
Definition BaseTalon.h:119
BaseTalonConfiguration(FeedbackDevice defaultFeedbackDevice)
Definition BaseTalon.h:171
LimitSwitchNormal forwardLimitSwitchNormal
Forward limit switch normally open/closed.
Definition BaseTalon.h:129
LimitSwitchNormal reverseLimitSwitchNormal
Reverse limit switch normally open/closed.
Definition BaseTalon.h:133
FeedbackDevice sum1Term
Feedback Device for Sum 1 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition BaseTalon.h:151
BaseTalonPIDSetConfiguration auxiliaryPID
Auxiliary PID configuration.
Definition BaseTalon.h:101
FeedbackDevice diff0Term
Feedback Device for Diff 0 Term Note the FeedbackDevice enum holds all possible sensor types.
Definition BaseTalon.h:160
BaseTalonPIDSetConfiguration primaryPID
Primary PID configuration.
Definition BaseTalon.h:97
Util class to help with BaseTalon's PID configs.
Definition BaseTalon.h:71
static bool SelectedFeedbackCoefficientDifferent(const BaseTalonPIDSetConfiguration &settings)
Definition BaseTalon.h:85
static bool SelectedFeedbackSensorDifferent(const BaseTalonPIDSetConfiguration &settings)
Determine if specified value is different from default.
Definition BaseTalon.h:84
Configurables available to BaseTalon's PID.
Definition BaseTalon.h:32
FeedbackDevice selectedFeedbackSensor
Feedback device for a particular PID loop.
Definition BaseTalon.h:41
BaseTalonPIDSetConfiguration(FeedbackDevice defaultFeedbackDevice)
Definition BaseTalon.h:43
std::string toString(std::string prependString)
Definition BaseTalon.h:60