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