CTRE Phoenix C++ 5.33.1
BaseMotorController.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2#pragma once
3
22
23#include <string>
24
25/* forward proto's */
26/** namespace ctre */
27namespace ctre {
28 /** namespace phoenix */
29 namespace phoenix {
30 /** namespace motorcontrol */
31 namespace motorcontrol {
32 /** namespace lowlevel */
33 namespace lowlevel {
34 class MotControllerWithBuffer_LowLevel;
35 class MotController_LowLevel;
36 }
37 }
38 }
39}
40
41namespace ctre {
42 namespace phoenix {
43 namespace motorcontrol {
44 /** namespace can */
45 namespace can {
46
47 /**
48 * Base set of configurables related to PID
49 */
51
52 /**
53 * Feedback coefficient of selected sensor
54 */
56
59 {
60 }
61
62 /**
63 * @return String representation of configs
64 */
65 std::string toString() {
66 return toString("");
67 }
68
69 /**
70 * @param prependString
71 * String to prepend to configs
72 * @return String representation of configs
73 */
74 std::string toString(const std::string& prependString) {
75 return prependString + ".selectedFeedbackCoefficient = " + std::to_string(selectedFeedbackCoefficient) + ";\n";
76
77 }
78 };// struct BasePIDSetConfiguration
79
80 /**
81 * Configurations for filters
82 */
84
85 /**
86 * Remote Sensor's device ID
87 */
89 /**
90 * The remote sensor device and signal type to bind.
91 */
93
97 {
98 }
99
100 /**
101 * @return string representation of currently selected configs
102 */
103 std::string toString() {
104 return toString("");
105 }
106
107 /**
108 * @param prependString String to prepend to all the configs
109 * @return string representation fo currently selected configs
110 */
111 std::string toString(std::string prependString) {
112 std::string retstr = prependString + ".remoteSensorDeviceID = " + std::to_string(remoteSensorDeviceID) + ";\n";
113 retstr += prependString + ".remoteSensorSource = " + RemoteSensorSourceRoutines::toString(remoteSensorSource) + ";\n";
114 return retstr;
115 }
116
117
118 }; // struct FilterConfiguration
119
120 /**
121 * Util class to help with filter configs
122 */
124 private:
125 static FilterConfiguration _default;
126 public:
127 /**
128 * Determine if specified value is different from default
129 * @param settings settings to compare against
130 * @return if specified value is different from default
131 * @{
132 */
133 static bool RemoteSensorDeviceIDDifferent(const FilterConfiguration& settings) { return (!(settings.remoteSensorDeviceID == _default.remoteSensorDeviceID)); }
134 static bool RemoteSensorSourceDifferent(const FilterConfiguration& settings) { return (!(settings.remoteSensorSource == _default.remoteSensorSource)); }
136 /** @} */
137 };
138
139 /**
140 * Configurables available to a slot
141 */
143
144 /**
145 * P Gain
146 *
147 * This is multiplied by closed loop error in sensor units.
148 * Note the closed loop output interprets a final value of 1023 as full output.
149 * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
150 */
151 double kP;
152 /**
153 * I Gain
154 *
155 * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
156 * Note the closed loop output interprets a final value of 1023 as full output.
157 * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
158 * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
159 */
160 double kI;
161 /**
162 * D Gain
163 *
164 * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
165 * Note the closed loop output interprets a final value of 1023 as full output.
166 * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
167 */
168 double kD;
169 /**
170 * F Gain
171 *
172 * See documentation for calculation details.
173 * If using velocity, motion magic, or motion profile,
174 * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
175 *
176 */
177 double kF;
178 /**
179 * Integral zone (in native units)
180 *
181 * If the (absolute) closed-loop error is outside of this zone, integral
182 * accumulator is automatically cleared. This ensures than integral wind up
183 * events will stop after the sensor gets far enough from its target.
184 */
186 /**
187 * Allowable closed loop error to neutral (in native units)
188 *
189 */
191 /**
192 * Max integral accumulator (in native units)
193 */
195 /**
196 * Peak output from closed loop [0,1]
197 */
199 /**
200 * Desired period of closed loop [1,64]ms
201 */
203
205 kP(0.0),
206 kI(0.0),
207 kD(0.0),
208 kF(0.0),
209 integralZone(0.0),
214 {
215 }
216
217 /**
218 * @return String representation of configs
219 */
220 std::string toString() {
221 return toString("");
222 }
223
224 /**
225 * @param prependString
226 * String to prepend to configs
227 * @return String representation of configs
228 */
229 std::string toString(std::string prependString) {
230
231 std::string retstr = prependString + ".kP = " + std::to_string(kP) + ";\n";
232 retstr += prependString + ".kI = " + std::to_string(kI) + ";\n";
233 retstr += prependString + ".kD = " + std::to_string(kD) + ";\n";
234 retstr += prependString + ".kF = " + std::to_string(kF) + ";\n";
235 retstr += prependString + ".integralZone = " + std::to_string(integralZone) + ";\n";
236 retstr += prependString + ".allowableClosedloopError = " + std::to_string(allowableClosedloopError) + ";\n";
237 retstr += prependString + ".maxIntegralAccumulator = " + std::to_string(maxIntegralAccumulator) + ";\n";
238 retstr += prependString + ".closedLoopPeakOutput = " + std::to_string(closedLoopPeakOutput) + ";\n";
239 retstr += prependString + ".closedLoopPeriod = " + std::to_string(closedLoopPeriod) + ";\n";
240
241 return retstr;
242
243 }
244
245 };// struct BaseSlotConfiguration
246
247 /**
248 * Util Class to help with slot configs
249 */
251 private:
252 static struct SlotConfiguration _default;
253 public:
254 /**
255 * Determine if specified value is different from default
256 * @param settings settings to compare against
257 * @return if specified value is different from default
258 * @{
259 */
260 static bool KPDifferent(const SlotConfiguration& settings) { return (!(settings.kP == _default.kP)); }
261 static bool KIDifferent(const SlotConfiguration& settings) { return (!(settings.kI == _default.kI)); }
262 static bool KDDifferent(const SlotConfiguration& settings) { return (!(settings.kD == _default.kD)); }
263 static bool KFDifferent(const SlotConfiguration& settings) { return (!(settings.kF == _default.kF)); }
264 static bool IntegralZoneDifferent(const SlotConfiguration& settings) { return (!(settings.integralZone == _default.integralZone)); }
265 static bool AllowableClosedloopErrorDifferent(const SlotConfiguration& settings) { return (!(settings.allowableClosedloopError == _default.allowableClosedloopError)); }
266 static bool MaxIntegralAccumulatorDifferent(const SlotConfiguration& settings) { return (!(settings.maxIntegralAccumulator == _default.maxIntegralAccumulator)); }
267 static bool ClosedLoopPeakOutputDifferent(const SlotConfiguration& settings) { return (!(settings.closedLoopPeakOutput == _default.closedLoopPeakOutput)); }
268 static bool ClosedLoopPeriodDifferent(const SlotConfiguration& settings) { return (!(settings.closedLoopPeriod == _default.closedLoopPeriod)); }
269 /** @} */
270 };
271
272
273 /**
274 * Configurables available to base motor controllers
275 */
277 /**
278 * Seconds to go from 0 to full in open loop
279 */
281 /**
282 * Seconds to go from 0 to full in closed loop
283 */
285 /**
286 * Peak output in forward direction [0,1]
287 */
289 /**
290 * Peak output in reverse direction [-1,0]
291 */
293 /**
294 * Nominal/Minimum output in forward direction [0,1]
295 */
297 /**
298 * Nominal/Minimum output in reverse direction [-1,0]
299 */
301 /**
302 * Neutral deadband [0.001, 0.25]
303 */
305 /**
306 * This is the max voltage to apply to the hbridge when voltage
307 * compensation is enabled. For example, if 10 (volts) is specified
308 * and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc)
309 * then the TalonSRX will attempt to apply a duty-cycle to produce 5V.
310 */
312 /**
313 * Number of samples in rolling average for voltage
314 */
316 /**
317 * Desired period for velocity measurement
318 */
320 /**
321 * Desired window for velocity measurement
322 */
324 /**
325 * Threshold for soft limits in forward direction (in raw sensor units)
326 */
328 /**
329 * Threshold for soft limits in reverse direction (in raw sensor units)
330 */
332 /**
333 * Enable forward soft limit
334 */
336 /**
337 * Enable reverse soft limit
338 */
340 /**
341 * Configuration for slot 0
342 */
344 /**
345 * Configuration for slot 1
346 */
348 /**
349 * Configuration for slot 2
350 */
352 /**
353 * Configuration for slot 3
354 */
356 /**
357 * PID polarity inversion
358 *
359 * Standard Polarity:
360 * Primary Output = PID0 + PID1,
361 * Auxiliary Output = PID0 - PID1,
362 *
363 * Inverted Polarity:
364 * Primary Output = PID0 - PID1,
365 * Auxiliary Output = PID0 + PID1,
366 */
368 /**
369 * Configuration for RemoteFilter 0
370 */
372 /**
373 * Configuration for RemoteFilter 1
374 */
376 /**
377 * Motion Magic cruise velocity in raw sensor units per 100 ms.
378 */
380 /**
381 * Motion Magic acceleration in (raw sensor units per 100 ms) per second.
382 */
384 /**
385 * Zero to use trapezoidal motion during motion magic. [1,8] for S-Curve, higher value for greater smoothing.
386 */
388 /**
389 * Motion profile base trajectory period in milliseconds.
390 *
391 * The period specified in a trajectory point will be
392 * added on to this value
393 */
395 /**
396 * Determine whether feedback sensor is continuous or not
397 */
399 /**
400 * Disable neutral'ing the motor when remote sensor is lost on CAN bus
401 */
403 /**
404 * Clear the position on forward limit
405 */
407 /**
408 * Clear the position on reverse limit
409 */
411 /**
412 * Clear the position on index
413 */
415 /**
416 * Disable neutral'ing the motor when remote limit switch is lost on CAN bus
417 */
419 /**
420 * Disable neutral'ing the motor when remote soft limit is lost on CAN bus
421 */
423 /**
424 * Number of edges per rotation for a tachometer sensor
425 */
427 /**
428 * Desired window size for a tachometer sensor
429 */
431 /**
432 * Enable motion profile trajectory point interpolation (defaults to true).
433 */
435
437 openloopRamp(0.0),
438 closedloopRamp(0.0),
440 peakOutputReverse(-1.0),
443 neutralDeadband(41.0 / 1023.0),
452 auxPIDPolarity(false),
467
468 {
469 }
470
471 /**
472 * @return String representation of configs
473 */
474 std::string toString() {
475 return toString("");
476 }
477
478 /**
479 * @param prependString
480 * String to prepend to configs
481 * @return String representation of configs
482 */
483 std::string toString(std::string prependString) {
484
485 std::string retstr = prependString + ".openloopRamp = " + std::to_string(openloopRamp) + ";\n";
486 retstr += prependString + ".closedloopRamp = " + std::to_string(closedloopRamp) + ";\n";
487 retstr += prependString + ".peakOutputForward = " + std::to_string(peakOutputForward) + ";\n";
488 retstr += prependString + ".peakOutputReverse = " + std::to_string(peakOutputReverse) + ";\n";
489 retstr += prependString + ".nominalOutputForward = " + std::to_string(nominalOutputForward) + ";\n";
490 retstr += prependString + ".nominalOutputReverse = " + std::to_string(nominalOutputReverse) + ";\n";
491 retstr += prependString + ".neutralDeadband = " + std::to_string(neutralDeadband) + ";\n";
492 retstr += prependString + ".voltageCompSaturation = " + std::to_string(voltageCompSaturation) + ";\n";
493 retstr += prependString + ".voltageMeasurementFilter = " + std::to_string(voltageMeasurementFilter) + ";\n";
494 retstr += prependString + ".velocityMeasurementPeriod = " + ctre::phoenix::sensors::SensorVelocityMeasPeriodRoutines::toString(velocityMeasurementPeriod) + ";\n";
495 retstr += prependString + ".velocityMeasurementWindow = " + std::to_string(velocityMeasurementWindow) + ";\n";
496 retstr += prependString + ".forwardSoftLimitThreshold = " + std::to_string(forwardSoftLimitThreshold) + ";\n";
497 retstr += prependString + ".reverseSoftLimitThreshold = " + std::to_string(reverseSoftLimitThreshold) + ";\n";
498 retstr += prependString + ".forwardSoftLimitEnable = " + std::to_string(forwardSoftLimitEnable) + ";\n";
499 retstr += prependString + ".reverseSoftLimitEnable = " + std::to_string(reverseSoftLimitEnable) + ";\n";
500 retstr += slot0.toString(prependString + ".slot0");
501 retstr += slot1.toString(prependString + ".slot1");
502 retstr += slot2.toString(prependString + ".slot2");
503 retstr += slot3.toString(prependString + ".slot3");
504 retstr += prependString + ".auxPIDPolarity = " + std::to_string(auxPIDPolarity) + ";\n";
505 retstr += remoteFilter0.toString(prependString + ".remoteFilter0");
506 retstr += remoteFilter1.toString(prependString + ".remoteFilter1");
507 retstr += prependString + ".motionCruiseVelocity = " + std::to_string(motionCruiseVelocity) + ";\n";
508 retstr += prependString + ".motionAcceleration = " + std::to_string(motionAcceleration) + ";\n";
509 retstr += prependString + ".motionCurveStrength = " + std::to_string(motionCurveStrength) + ";\n";
510 retstr += prependString + ".motionProfileTrajectoryPeriod = " + std::to_string(motionProfileTrajectoryPeriod) + ";\n";
511 retstr += prependString + ".feedbackNotContinuous = " + std::to_string(feedbackNotContinuous) + ";\n";
512 retstr += prependString + ".remoteSensorClosedLoopDisableNeutralOnLOS = " + std::to_string(remoteSensorClosedLoopDisableNeutralOnLOS) + ";\n";
513 retstr += prependString + ".clearPositionOnLimitF = " + std::to_string(clearPositionOnLimitF) + ";\n";
514 retstr += prependString + ".clearPositionOnLimitR = " + std::to_string(clearPositionOnLimitR) + ";\n";
515 retstr += prependString + ".clearPositionOnQuadIdx = " + std::to_string(clearPositionOnQuadIdx) + ";\n";
516 retstr += prependString + ".limitSwitchDisableNeutralOnLOS = " + std::to_string(limitSwitchDisableNeutralOnLOS) + ";\n";
517 retstr += prependString + ".softLimitDisableNeutralOnLOS = " + std::to_string(softLimitDisableNeutralOnLOS) + ";\n";
518 retstr += prependString + ".pulseWidthPeriod_EdgesPerRot = " + std::to_string(pulseWidthPeriod_EdgesPerRot) + ";\n";
519 retstr += prependString + ".pulseWidthPeriod_FilterWindowSz = " + std::to_string(pulseWidthPeriod_FilterWindowSz) + ";\n";
520 retstr += prependString + ".trajectoryInterpolationEnable = " + std::to_string(trajectoryInterpolationEnable) + ";\n";
521
522 retstr += CustomParamConfiguration::toString(prependString);
523
524 return retstr;
525 }
526
527
528 };// struct BaseMotorControllerConfiguration
529
530 /**
531 * Util class to help with Base Motor Controller configs
532 */
534 private:
535 static struct BaseMotorControllerConfiguration _default;
536 public:
537 /**
538 * Determine if specified value is different from default
539 * @param settings settings to compare against
540 * @return if specified value is different from default
541 * @{
542 */
543 static bool OpenloopRampDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.openloopRamp == _default.openloopRamp)) || !settings.enableOptimizations; }
544 static bool ClosedloopRampDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.closedloopRamp == _default.closedloopRamp)) || !settings.enableOptimizations; }
545 static bool PeakOutputForwardDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.peakOutputForward == _default.peakOutputForward)) || !settings.enableOptimizations; }
546 static bool PeakOutputReverseDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.peakOutputReverse == _default.peakOutputReverse)) || !settings.enableOptimizations; }
547 static bool NominalOutputForwardDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.nominalOutputForward == _default.nominalOutputForward)) || !settings.enableOptimizations; }
548 static bool NominalOutputReverseDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.nominalOutputReverse == _default.nominalOutputReverse)) || !settings.enableOptimizations; }
549 static bool NeutralDeadbandDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.neutralDeadband == _default.neutralDeadband)) || !settings.enableOptimizations; }
550 static bool VoltageCompSaturationDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.voltageCompSaturation == _default.voltageCompSaturation)) || !settings.enableOptimizations; }
558 static bool AuxPIDPolarityDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.auxPIDPolarity == _default.auxPIDPolarity)) || !settings.enableOptimizations; }
559 static bool MotionCruiseVelocityDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.motionCruiseVelocity == _default.motionCruiseVelocity)) || !settings.enableOptimizations; }
560 static bool MotionAccelerationDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.motionAcceleration == _default.motionAcceleration)) || !settings.enableOptimizations; }
561 static bool MotionSCurveStrength(const BaseMotorControllerConfiguration& settings) { return (!(settings.motionCurveStrength == _default.motionCurveStrength)) || !settings.enableOptimizations; }
563 static bool FeedbackNotContinuousDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.feedbackNotContinuous == _default.feedbackNotContinuous)) || !settings.enableOptimizations; }
565 static bool ClearPositionOnLimitFDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.clearPositionOnLimitF == _default.clearPositionOnLimitF)) || !settings.enableOptimizations; }
566 static bool ClearPositionOnLimitRDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.clearPositionOnLimitR == _default.clearPositionOnLimitR)) || !settings.enableOptimizations; }
573 /** @} */
574 };
575 /**
576 * Base motor controller features for all CTRE CAN motor controllers.
577 */
578 class BaseMotorController : public virtual IMotorController {
579 private:
582
583 double m_setPoint = 0;
585
586 ctre::phoenix::ErrorCode ConfigureSlotPrivate(const SlotConfiguration& slot, int slotIdx, int timeoutMs, bool enableOptimizations);
587 ctre::phoenix::ErrorCode ConfigureFilter(const FilterConfiguration& filter, int ordinal, int timeoutMs, bool enableOptimizations);
588
589 /**
590 * Handle of device
591 */
592 void* m_handle;
593
594 bool _isVcompEn = false;
595
597
598 protected:
600
601 /**
602 * Configures all base persistant settings.
603 *
604 * @param allConfigs Object with all of the base persistant settings
605 * @param timeoutMs
606 * Timeout value in ms. If nonzero, function will wait for
607 * config success and report an error if it times out.
608 * If zero, no blocking or checking is performed.
609 *
610 * @return Error Code generated by function. 0 indicates no error.
611 */
613 /**
614 * Gets all base persistant settings.
615 *
616 * @param allConfigs Object with all of the base persistant settings
617 * @param timeoutMs
618 * Timeout value in ms. If nonzero, function will wait for
619 * config success and report an error if it times out.
620 * If zero, no blocking or checking is performed.
621 */
622 virtual void BaseGetAllConfigs(BaseMotorControllerConfiguration& allConfigs, int timeoutMs);
623 /**
624 * Gets all base PID set persistant settings.
625 *
626 * @param pid Object with all of the base PID set persistant settings
627 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
628 * @param timeoutMs
629 * Timeout value in ms. If nonzero, function will wait for
630 * config success and report an error if it times out.
631 * If zero, no blocking or checking is performed.
632 */
633 virtual void BaseGetPIDConfigs(BasePIDSetConfiguration& pid, int pidIdx, int timeoutMs);
634
635 //------ General Status ----------//
636 /**
637 * Gets the output current of the motor controller.
638 * In the case of TalonSRX class, this routine returns supply current for legacy reasons. In order to get the "true" output current, call GetStatorCurrent().
639 * In the case of TalonFX class, this routine returns the true output stator current.
640 *
641 * [[deprecated("Use GetStatorCurrent/GetSupplyCurrent instead.")]]
642 *
643 * @return The output current (in amps).
644 */
645 virtual double GetOutputCurrent();
646
647 public:
648 /**
649 * Constructor for motor controllers.
650 *
651 * @param arbId Device ID [0,62]
652 * @param model String model of device.
653 * Examples: "Talon SRX", "Talon FX", "Victor SPX".
654 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
655 * or a CANivore device name or serial number
656 */
657 BaseMotorController(int deviceNumber, const char* model, std::string const &canbus = "");
662
663 /**
664 * Destructs all motor controller objects
665 */
667
668 /**
669 * Returns the Device ID
670 *
671 * @return Device number.
672 */
673 virtual int GetDeviceID();
674 // ------ Set output routines. ----------//
675 /**
676 * Sets the appropriate output on the talon, depending on the mode.
677 * @param mode The output mode to apply.
678 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
679 * In Current mode, output value is in amperes.
680 * In Velocity mode, output value is in position change / 100ms.
681 * In Position mode, output value is in encoder ticks or an analog value,
682 * depending on the sensor.
683 * In Follower mode, the output value is the integer device ID of the talon to
684 * duplicate.
685 *
686 * @param value The setpoint value, as described above.
687 *
688 *
689 * Standard Driving Example:
690 * _talonLeft.set(ControlMode.PercentOutput, leftJoy);
691 * _talonRght.set(ControlMode.PercentOutput, rghtJoy);
692 */
693 virtual void Set(ControlMode mode, double value);
694 /**
695 * @param mode Sets the appropriate output on the talon, depending on the mode.
696 * @param demand0 The output value to apply.
697 * such as advanced feed forward and/or auxiliary close-looping in firmware.
698 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
699 * In Current mode, output value is in amperes.
700 * In Velocity mode, output value is in position change / 100ms.
701 * In Position mode, output value is in encoder ticks or an analog value,
702 * depending on the sensor. See
703 * In Follower mode, the output value is the integer device ID of the talon to
704 * duplicate.
705 *
706 * @param demand1Type The demand type for demand1.
707 * Neutral: Ignore demand1 and apply no change to the demand0 output.
708 * AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary
709 * PID is always executed as standard Position PID control.
710 * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
711 * demand0 output. In PercentOutput the demand0 output is the motor output,
712 * and in closed-loop modes the demand0 output is the output of PID0.
713 * @param demand1 Supplmental output value.
714 * AuxPID: Target position in Sensor Units
715 * ArbitraryFeedForward: Percent Output between -1.0 and 1.0
716 *
717 *
718 * Arcade Drive Example:
719 * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
720 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
721 *
722 * Drive Straight Example:
723 * Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
724 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
725 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
726 *
727 * Drive Straight to a Distance Example:
728 * Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
729 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
730 * _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
731 */
732 virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1);
733 /**
734 * Neutral the motor output by setting control mode to disabled.
735 */
736 virtual void NeutralOutput();
737 /**
738 * Sets the mode of operation during neutral throttle output.
739 *
740 * @param neutralMode
741 * The desired mode of operation when the Controller output
742 * throttle is neutral (ie brake/coast)
743 **/
744 virtual void SetNeutralMode(NeutralMode neutralMode);
745 //------ Invert behavior ----------//
746 /**
747 * Sets the phase of the sensor. Use when controller forward/reverse output
748 * doesn't correlate to appropriate forward/reverse reading of sensor.
749 * Pick a value so that positive PercentOutput yields a positive change in sensor.
750 * After setting this, user can freely call SetInverted() with any value.
751 *
752 * @param PhaseSensor
753 * Indicates whether to invert the phase of the sensor.
754 */
755 virtual void SetSensorPhase(bool PhaseSensor);
756 /**
757 * Inverts the hbridge output of the motor controller.
758 *
759 * This does not impact sensor phase and should not be used to correct sensor polarity.
760 *
761 * This will invert the hbridge output but NOT the LEDs.
762 * This ensures....
763 * - Green LEDs always represents positive request from robot-controller/closed-looping mode.
764 * - Green LEDs correlates to forward limit switch.
765 * - Green LEDs correlates to forward soft limit.
766 *
767 * @param invert
768 * Invert state to set.
769 */
770 virtual void SetInverted(bool invert);
771 /**
772 * Inverts the hbridge output of the motor controller in relation to the master if present
773 *
774 * This does not impact sensor phase and should not be used to correct sensor polarity.
775 *
776 * This will allow you to either:
777 * - Not invert the motor
778 * - Invert the motor
779 * - Always follow the master regardless of master's inversion
780 * - Always oppose the master regardless of master's inversion
781 *
782 * @param invertType
783 * Invert state to set.
784 */
785 virtual void SetInverted(InvertType invertType);
786 /**
787 * @return invert setting of motor output.
788 */
789 virtual bool GetInverted() const;
790 //----- Factory Default Configuration -----//
791 /**
792 * Revert all configurations to factory default values.
793 * Use this before your individual config* calls to avoid having to config every single param.
794 *
795 * Alternatively you can use the configAllSettings routine.
796 *
797 * @param timeoutMs
798 * Timeout value in ms. Function will generate error if config is
799 * not successful within timeout.
800 * @return Error Code generated by function. 0 indicates no error.
801 */
803 //----- general output shaping ------------------//
804 /**
805 * Configures the open-loop ramp rate of throttle output.
806 *
807 * @param secondsFromNeutralToFull
808 * Minimum desired time to go from neutral to full throttle. A
809 * value of '0' will disable the ramp.
810 * @param timeoutMs
811 * Timeout value in ms. If nonzero, function will wait for
812 * config success and report an error if it times out.
813 * If zero, no blocking or checking is performed.
814 * @return Error Code generated by function. 0 indicates no error.
815 */
816 virtual ctre::phoenix::ErrorCode ConfigOpenloopRamp(double secondsFromNeutralToFull,
817 int timeoutMs = 0);
818 /**
819 * Configures the closed-loop ramp rate of throttle output.
820 *
821 * @param secondsFromNeutralToFull
822 * Minimum desired time to go from neutral to full throttle. A
823 * value of '0' will disable the ramp.
824 * @param timeoutMs
825 * Timeout value in ms. If nonzero, function will wait for
826 * config success and report an error if it times out.
827 * If zero, no blocking or checking is performed.
828 * @return Error Code generated by function. 0 indicates no error.
829 */
830 virtual ctre::phoenix::ErrorCode ConfigClosedloopRamp(double secondsFromNeutralToFull,
831 int timeoutMs = 0);
832 /**
833 * Configures the forward peak output percentage.
834 *
835 * @param percentOut
836 * Desired peak output percentage. [0,1]
837 * @param timeoutMs
838 * Timeout value in ms. If nonzero, function will wait for
839 * config success and report an error if it times out.
840 * If zero, no blocking or checking is performed.
841 * @return Error Code generated by function. 0 indicates no error.
842 */
843 virtual ctre::phoenix::ErrorCode ConfigPeakOutputForward(double percentOut, int timeoutMs = 0);
844 /**
845 * Configures the reverse peak output percentage.
846 *
847 * @param percentOut
848 * Desired peak output percentage.
849 * @param timeoutMs
850 * Timeout value in ms. If nonzero, function will wait for
851 * config success and report an error if it times out.
852 * If zero, no blocking or checking is performed.
853 * @return Error Code generated by function. 0 indicates no error.
854 */
855 virtual ctre::phoenix::ErrorCode ConfigPeakOutputReverse(double percentOut, int timeoutMs = 0);
856 /**
857 * Configures the forward nominal output percentage.
858 *
859 * @param percentOut
860 * Nominal (minimum) percent output. [0,+1]
861 * @param timeoutMs
862 * Timeout value in ms. If nonzero, function will wait for
863 * config success and report an error if it times out.
864 * If zero, no blocking or checking is performed.
865 * @return Error Code generated by function. 0 indicates no error.
866 */
868 int timeoutMs = 0);
869 /**
870 * Configures the reverse nominal output percentage.
871 *
872 * @param percentOut
873 * Nominal (minimum) percent output. [-1,0]
874 * @param timeoutMs
875 * Timeout value in ms. If nonzero, function will wait for
876 * config success and report an error if it times out.
877 * If zero, no blocking or checking is performed.
878 * @return Error Code generated by function. 0 indicates no error.
879 */
881 int timeoutMs = 0);
882 /**
883 * Configures the output deadband percentage.
884 *
885 * @param percentDeadband
886 * Desired deadband percentage. Minimum is 0.1%, Maximum is 25%.
887 * Pass 0.04 for 4% (factory default).
888 * @param timeoutMs
889 * Timeout value in ms. If nonzero, function will wait for
890 * config success and report an error if it times out.
891 * If zero, no blocking or checking is performed.
892 * @return Error Code generated by function. 0 indicates no error.
893 */
894 virtual ctre::phoenix::ErrorCode ConfigNeutralDeadband(double percentDeadband,
895 int timeoutMs = 0);
896 //------ Voltage Compensation ----------//
897 /**
898 * Configures the Voltage Compensation saturation voltage.
899 *
900 * @param voltage
901 * This is the max voltage to apply to the hbridge when voltage
902 * compensation is enabled. For example, if 10 (volts) is specified
903 * and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc)
904 * then the TalonSRX will attempt to apply a duty-cycle to produce 5V.
905 * @param timeoutMs
906 * Timeout value in ms. If nonzero, function will wait for
907 * config success and report an error if it times out.
908 * If zero, no blocking or checking is performed.
909 * @return Error Code generated by function. 0 indicates no error.
910 */
911 virtual ctre::phoenix::ErrorCode ConfigVoltageCompSaturation(double voltage, int timeoutMs = 0);
912 /**
913 * Configures the voltage measurement filter.
914 *
915 * @param filterWindowSamples
916 * Number of samples in the rolling average of voltage
917 * measurement.
918 * @param timeoutMs
919 * Timeout value in ms. If nonzero, function will wait for
920 * config success and report an error if it times out.
921 * If zero, no blocking or checking is performed.
922 * @return Error Code generated by function. 0 indicates no error.
923 */
925 int timeoutMs = 0);
926 /**
927 * Enables voltage compensation. If enabled, voltage compensation works in
928 * all control modes.
929 *
930 * Be sure to configure the saturation voltage before enabling this.
931 *
932 * @param enable
933 * Enable state of voltage compensation.
934 **/
935 virtual void EnableVoltageCompensation(bool enable);
936 /**
937 * Returns the enable state of Voltage Compensation that the caller has set.
938 *
939 * @return TRUE if voltage compensation is enabled.
940 */
942
943 //------ General Status ----------//
944 /**
945 * Gets the bus voltage seen by the device.
946 *
947 * @return The bus voltage value (in volts).
948 */
949 virtual double GetBusVoltage();
950 /**
951 * Gets the output percentage of the motor controller.
952 *
953 * @return Output of the motor controller (in percent).
954 */
955 virtual double GetMotorOutputPercent();
956 /**
957 * @return applied voltage to motor in volts.
958 */
959 virtual double GetMotorOutputVoltage();
960 /**
961 * Gets the temperature of the motor controller.
962 *
963 * @return Temperature of the motor controller (in 'C)
964 */
965 virtual double GetTemperature();
966
967 //------ sensor selection ----------//
968 /**
969 * Select the remote feedback device for the motor controller.
970 * Most CTRE CAN motor controllers will support remote sensors over CAN.
971 *
972 * @param feedbackDevice
973 * Remote Feedback Device to select.
974 * @param pidIdx
975 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
976 * @param timeoutMs
977 * Timeout value in ms. If nonzero, function will wait for
978 * config success and report an error if it times out.
979 * If zero, no blocking or checking is performed.
980 * @return Error Code generated by function. 0 indicates no error.
981 */
983 RemoteFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
984 /**
985 * Select the feedback device for the motor controller.
986 *
987 * @param feedbackDevice
988 * Feedback Device to select.
989 * @param pidIdx
990 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
991 * @param timeoutMs
992 * Timeout value in ms. If nonzero, function will wait for
993 * config success and report an error if it times out.
994 * If zero, no blocking or checking is performed.
995 * @return Error Code generated by function. 0 indicates no error.
996 */
998 FeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
999 /**
1000 * The Feedback Coefficient is a scalar applied to the value of the
1001 * feedback sensor. Useful when you need to scale your sensor values
1002 * within the closed-loop calculations. Default value is 1.
1003 *
1004 * Selected Feedback Sensor register in firmware is the decoded sensor value
1005 * multiplied by the Feedback Coefficient.
1006 *
1007 * @param coefficient
1008 * Feedback Coefficient value. Maximum value of 1.
1009 * Resolution is 1/(2^16). Cannot be 0.
1010 * @param pidIdx
1011 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1012 * @param timeoutMs
1013 * Timeout value in ms. If nonzero, function will wait for
1014 * config success and report an error if it times out.
1015 * If zero, no blocking or checking is performed.
1016 * @return Error Code generated by function. 0 indicates no error.
1017 */
1019 double coefficient, int pidIdx = 0, int timeoutMs = 0);
1020 /**
1021 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1022 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1023 * as a PID source for closed-loop features.
1024 *
1025 * @param deviceID
1026 * The device ID of the remote sensor device.
1027 * @param remoteSensorSource
1028 * The remote sensor device and signal type to bind.
1029 * @param remoteOrdinal
1030 * 0 for configuring Remote Sensor 0,
1031 * 1 for configuring Remote Sensor 1
1032 * @param timeoutMs
1033 * Timeout value in ms. If nonzero, function will wait for
1034 * config success and report an error if it times out.
1035 * If zero, no blocking or checking is performed.
1036 * @return Error Code generated by function. 0 indicates no error.
1037 */
1038 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
1039 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
1040 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
1042 RemoteSensorSource remoteSensorSource, int remoteOrdinal,
1043 int timeoutMs = 0);
1044 /**
1045 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1046 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1047 * as a PID source for closed-loop features.
1048 *
1049 * @param canCoderRef
1050 * CANCoder device reference to use.
1051 * @param remoteOrdinal
1052 * 0 for configuring Remote Sensor 0,
1053 * 1 for configuring Remote Sensor 1
1054 * @param timeoutMs
1055 * Timeout value in ms. If nonzero, function will wait for
1056 * config success and report an error if it times out.
1057 * If zero, no blocking or checking is performed.
1058 * @return Error Code generated by function. 0 indicates no error.
1059 */
1060 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
1061 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
1062 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
1063 virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::sensors::CANCoder &canCoderRef, int remoteOrdinal, int timeoutMs = 0);
1064 /**
1065 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1066 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1067 * as a PID source for closed-loop features.
1068 *
1069 * @param talonRef
1070 * Talon device reference to use.
1071 * @param remoteOrdinal
1072 * 0 for configuring Remote Sensor 0,
1073 * 1 for configuring Remote Sensor 1
1074 * @param timeoutMs
1075 * Timeout value in ms. If nonzero, function will wait for
1076 * config success and report an error if it times out.
1077 * If zero, no blocking or checking is performed.
1078 * @return Error Code generated by function. 0 indicates no error.
1079 */
1080 virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::motorcontrol::can::BaseTalon &talonRef, int remoteOrdinal, int timeoutMs = 0);
1081 /**
1082 * Select what sensor term should be bound to switch feedback device.
1083 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
1084 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
1085 * The four terms are specified with this routine. Then Sensor Sum/Difference
1086 * can be selected for closed-looping.
1087 *
1088 * @param sensorTerm Which sensor term to bind to a feedback source.
1089 * @param feedbackDevice The sensor signal to attach to sensorTerm.
1090 * @param timeoutMs
1091 * Timeout value in ms. If nonzero, function will wait for
1092 * config success and report an error if it times out.
1093 * If zero, no blocking or checking is performed.
1094 * @return Error Code generated by function. 0 indicates no error.
1095 */
1097 FeedbackDevice feedbackDevice, int timeoutMs = 0);
1098 /**
1099 * Select what sensor term should be bound to switch feedback device.
1100 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
1101 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
1102 * The four terms are specified with this routine. Then Sensor Sum/Difference
1103 * can be selected for closed-looping.
1104 *
1105 * @param sensorTerm Which sensor term to bind to a feedback source.
1106 * @param feedbackDevice The sensor signal to attach to sensorTerm.
1107 * @param timeoutMs
1108 * Timeout value in ms. If nonzero, function will wait for
1109 * config success and report an error if it times out.
1110 * If zero, no blocking or checking is performed.
1111 * @return Error Code generated by function. 0 indicates no error.
1112 */
1114 RemoteFeedbackDevice feedbackDevice, int timeoutMs = 0);
1115
1116 //------- sensor status --------- //
1117 /**
1118 * Get the selected sensor position (in raw sensor units).
1119 *
1120 * @param pidIdx
1121 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. See
1122 * Phoenix-Documentation for how to interpret.
1123 *
1124 * @return Position of selected sensor (in raw sensor units).
1125 */
1126 virtual double GetSelectedSensorPosition(int pidIdx = 0);
1127 /**
1128 * Get the selected sensor velocity.
1129 *
1130 * @param pidIdx
1131 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1132 * @return selected sensor (in raw sensor units) per 100ms.
1133 * See Phoenix-Documentation for how to interpret.
1134 */
1135 virtual double GetSelectedSensorVelocity(int pidIdx = 0);
1136 /**
1137 * Sets the sensor position to the given value.
1138 *
1139 * @param sensorPos
1140 * Position to set for the selected sensor (in raw sensor units).
1141 * @param pidIdx
1142 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1143 * @param timeoutMs
1144 * Timeout value in ms. If nonzero, function will wait for
1145 * config success and report an error if it times out.
1146 * If zero, no blocking or checking is performed.
1147 * @return Error Code generated by function. 0 indicates no error.
1148 */
1149 virtual ctre::phoenix::ErrorCode SetSelectedSensorPosition(double sensorPos, int pidIdx = 0, int timeoutMs = 50);
1150 //------ status frame period changes ----------//
1151 /**
1152 * Sets the period of the given control frame.
1153 *
1154 * @param frame
1155 * Frame whose period is to be changed.
1156 * @param periodMs
1157 * Period in ms for the given frame.
1158 * @return Error Code generated by function. 0 indicates no error.
1159 */
1161 /**
1162 * Sets the period of the given status frame.
1163 *
1164 * User ensure CAN Bus utilization is not high.
1165 *
1166 * This setting is not persistent and is lost when device is reset. If this
1167 * is a concern, calling application can use HasResetOccurred() to determine if the
1168 * status frame needs to be reconfigured.
1169 *
1170 * @param frame
1171 * Frame whose period is to be changed.
1172 * @param periodMs
1173 * Period in ms for the given frame.
1174 * @param timeoutMs
1175 * Timeout value in ms. If nonzero, function will wait for config
1176 * success and report an error if it times out. If zero, no
1177 * blocking or checking is performed.
1178 * @return Error Code generated by function. 0 indicates no error.
1179 */
1181 int timeoutMs = 0);
1182 /**
1183 * Sets the period of the given status frame.
1184 *
1185 * User ensure CAN Bus utilization is not high.
1186 *
1187 * This setting is not persistent and is lost when device is reset. If this
1188 * is a concern, calling application can use HasResetOccurred() to determine if the
1189 * status frame needs to be reconfigured.
1190 *
1191 * @param frame
1192 * Frame whose period is to be changed.
1193 * @param periodMs
1194 * Period in ms for the given frame.
1195 * @param timeoutMs
1196 * Timeout value in ms. If nonzero, function will wait for config
1197 * success and report an error if it times out. If zero, no
1198 * blocking or checking is performed.
1199 * @return Error Code generated by function. 0 indicates no error.
1200 */
1202 uint8_t periodMs, int timeoutMs = 0);
1203 /**
1204 * Gets the period of the given status frame.
1205 *
1206 * @param frame
1207 * Frame to get the period of.
1208 * @param timeoutMs
1209 * Timeout value in ms. If nonzero, function will wait for
1210 * config success and report an error if it times out.
1211 * If zero, no blocking or checking is performed.
1212 * @return Period of the given status frame.
1213 */
1214 virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs = 0);
1215 /**
1216 * Gets the period of the given status frame.
1217 *
1218 * @param frame
1219 * Frame to get the period of.
1220 * @param timeoutMs
1221 * Timeout value in ms. If nonzero, function will wait for
1222 * config success and report an error if it times out.
1223 * If zero, no blocking or checking is performed.
1224 * @return Period of the given status frame.
1225 */
1226 virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs = 0);
1227 //----- velocity signal conditionaing ------//
1228 /**
1229 * Sets the period over which velocity measurements are taken.
1230 *
1231 * @param period
1232 * Desired period for the velocity measurement. @see
1233 * #SensorVelocityMeasPeriod
1234 * @param timeoutMs
1235 * Timeout value in ms. If nonzero, function will wait for
1236 * config success and report an error if it times out.
1237 * If zero, no blocking or checking is performed.
1238 * @return Error Code generated by function. 0 indicates no error.
1239 */
1241 int timeoutMs = 0);
1242
1243 [[deprecated("Use the overload with SensorVelocityMeasPeriod instead.")]]
1245 int timeoutMs = 0);
1246 /**
1247 * Sets the number of velocity samples used in the rolling average velocity
1248 * measurement.
1249 *
1250 * @param windowSize
1251 * Number of samples in the rolling average of velocity
1252 * measurement. Valid values are 1,2,4,8,16,32. If another value
1253 * is specified, it will truncate to nearest support value.
1254 * @param timeoutMs
1255 * Timeout value in ms. If nonzero, function will wait for config
1256 * success and report an error if it times out. If zero, no
1257 * blocking or checking is performed.
1258 * @return Error Code generated by function. 0 indicates no error.
1259 */
1261 int timeoutMs = 0);
1262 //------ remote limit switch ----------//
1263 /**
1264 * Configures the forward limit switch for a remote source. For example, a
1265 * CAN motor controller may need to monitor the Limit-F pin of another Talon
1266 * or CANifier.
1267 *
1268 * @param type
1269 * Remote limit switch source. User can choose between a remote
1270 * Talon SRX, CANifier, or deactivate the feature.
1271 * @param normalOpenOrClose
1272 * Setting for normally open, normally closed, or disabled. This
1273 * setting matches the Phoenix Tuner drop down.
1274 * @param deviceID
1275 * Device ID of remote source (Talon SRX or CANifier device ID).
1276 * @param timeoutMs
1277 * Timeout value in ms. If nonzero, function will wait for config
1278 * success and report an error if it times out. If zero, no
1279 * blocking or checking is performed.
1280 * @return Error Code generated by function. 0 indicates no error.
1281 */
1283 RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1284 int deviceID, int timeoutMs = 0);
1285 /**
1286 * Configures the reverse limit switch for a remote source. For example, a
1287 * CAN motor controller may need to monitor the Limit-R pin of another Talon
1288 * or CANifier.
1289 *
1290 * @param type
1291 * Remote limit switch source. User can choose between a remote
1292 * Talon SRX, CANifier, or deactivate the feature.
1293 * @param normalOpenOrClose
1294 * Setting for normally open, normally closed, or disabled. This
1295 * setting matches the Phoenix Tuner drop down.
1296 * @param deviceID
1297 * Device ID of remote source (Talon SRX or CANifier device ID).
1298 * @param timeoutMs
1299 * Timeout value in ms. If nonzero, function will wait for config
1300 * success and report an error if it times out. If zero, no
1301 * blocking or checking is performed.
1302 * @return Error Code generated by function. 0 indicates no error.
1303 */
1305 RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1306 int deviceID, int timeoutMs = 0);
1307 /**
1308 * Sets the enable state for limit switches.
1309 *
1310 * @param enable
1311 * Enable state for limit switches.
1312 **/
1314 //------ local limit switch ----------//
1315 /**
1316 * Configures a limit switch for a local/remote source.
1317 *
1318 * For example, a CAN motor controller may need to monitor the Limit-R pin
1319 * of another Talon, CANifier, or local Gadgeteer feedback connector.
1320 *
1321 * If the sensor is remote, a device ID of zero is assumed. If that's not
1322 * desired, use the four parameter version of this function.
1323 *
1324 * @param type
1325 * Limit switch source. User can choose
1326 * between the feedback connector, remote Talon SRX, CANifier, or
1327 * deactivate the feature.
1328 * @param normalOpenOrClose
1329 * Setting for normally open, normally closed, or disabled. This
1330 * setting matches the Phoenix Tuner drop down.
1331 * @param timeoutMs
1332 * Timeout value in ms. If nonzero, function will wait for config
1333 * success and report an error if it times out. If zero, no
1334 * blocking or checking is performed.
1335 * @return Error Code generated by function. 0 indicates no error.
1336 */
1338 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
1339 /**
1340 * Configures a limit switch for a local/remote source.
1341 *
1342 * For example, a CAN motor controller may need to monitor the Limit-R pin
1343 * of another Talon, CANifier, or local Gadgeteer feedback connector.
1344 *
1345 * If the sensor is remote, a device ID of zero is assumed. If that's not
1346 * desired, use the four parameter version of this function.
1347 *
1348 * @param type
1349 * Limit switch source. User can choose
1350 * between the feedback connector, remote Talon SRX, CANifier, or
1351 * deactivate the feature.
1352 * @param normalOpenOrClose
1353 * Setting for normally open, normally closed, or disabled. This
1354 * setting matches the Phoenix Tuner drop down.
1355 * @param timeoutMs
1356 * Timeout value in ms. If nonzero, function will wait for config
1357 * success and report an error if it times out. If zero, no
1358 * blocking or checking is performed.
1359 * @return Error Code generated by function. 0 indicates no error.
1360 */
1362 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
1363 //------ soft limit ----------//
1364 /**
1365 * Configures the forward soft limit threhold.
1366 *
1367 * @param forwardSensorLimit
1368 * Forward Sensor Position Limit (in raw sensor units).
1369 * @param timeoutMs
1370 * Timeout value in ms. If nonzero, function will wait for
1371 * config success and report an error if it times out.
1372 * If zero, no blocking or checking is performed.
1373 * @return Error Code generated by function. 0 indicates no error.
1374 */
1376 int timeoutMs = 0);
1377 /**
1378 * Configures the reverse soft limit threshold.
1379 *
1380 * @param reverseSensorLimit
1381 * Reverse Sensor Position Limit (in raw sensor units).
1382 * @param timeoutMs
1383 * Timeout value in ms. If nonzero, function will wait for
1384 * config success and report an error if it times out.
1385 * If zero, no blocking or checking is performed.
1386 * @return Error Code generated by function. 0 indicates no error.
1387 */
1389 int timeoutMs = 0);
1390 /**
1391 * Configures the forward soft limit enable.
1392 *
1393 * @param enable
1394 * Forward Sensor Position Limit Enable.
1395 * @param timeoutMs
1396 * Timeout value in ms. If nonzero, function will wait for
1397 * config success and report an error if it times out.
1398 * If zero, no blocking or checking is performed.
1399 * @return Error Code generated by function. 0 indicates no error.
1400 */
1402 int timeoutMs = 0);
1403 /**
1404 * Configures the reverse soft limit enable.
1405 *
1406 * @param enable
1407 * Reverse Sensor Position Limit Enable.
1408 * @param timeoutMs
1409 * Timeout value in ms. If nonzero, function will wait for config
1410 * success and report an error if it times out. If zero, no
1411 * blocking or checking is performed.
1412 * @return Error Code generated by function. 0 indicates no error.
1413 */
1415 int timeoutMs = 0);
1416 /**
1417 * Can be used to override-disable the soft limits.
1418 * This function can be used to quickly disable soft limits without
1419 * having to modify the persistent configuration.
1420 *
1421 * @param enable
1422 * Enable state for soft limit switches.
1423 */
1424 virtual void OverrideSoftLimitsEnable(bool enable);
1425 //------ Current Lim ----------//
1426 /* not available in base */
1427 //------ General Close loop ----------//
1428 /**
1429 * Sets the 'P' constant in the given parameter slot.
1430 * This is multiplied by closed loop error in sensor units.
1431 * Note the closed loop output interprets a final value of 1023 as full output.
1432 * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
1433 *
1434 * @param slotIdx
1435 * Parameter slot for the constant.
1436 * @param value
1437 * Value of the P constant.
1438 * @param timeoutMs
1439 * Timeout value in ms. If nonzero, function will wait for
1440 * config success and report an error if it times out.
1441 * If zero, no blocking or checking is performed.
1442 * @return Error Code generated by function. 0 indicates no error.
1443 */
1444 virtual ctre::phoenix::ErrorCode Config_kP(int slotIdx, double value, int timeoutMs = 0);
1445 /**
1446 * Sets the 'I' constant in the given parameter slot.
1447 * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
1448 * Note the closed loop output interprets a final value of 1023 as full output.
1449 * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
1450 * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
1451 *
1452 * @param slotIdx
1453 * Parameter slot for the constant.
1454 * @param value
1455 * Value of the I constant.
1456 * @param timeoutMs
1457 * Timeout value in ms. If nonzero, function will wait for
1458 * config success and report an error if it times out.
1459 * If zero, no blocking or checking is performed.
1460 * @return Error Code generated by function. 0 indicates no error.
1461 */
1462 virtual ctre::phoenix::ErrorCode Config_kI(int slotIdx, double value, int timeoutMs = 0);
1463 /**
1464 * Sets the 'D' constant in the given parameter slot.
1465 *
1466 * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
1467 * Note the closed loop output interprets a final value of 1023 as full output.
1468 * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
1469 *
1470 * @param slotIdx
1471 * Parameter slot for the constant.
1472 * @param value
1473 * Value of the D constant.
1474 * @param timeoutMs
1475 * Timeout value in ms. If nonzero, function will wait for
1476 * config success and report an error if it times out.
1477 * If zero, no blocking or checking is performed.
1478 * @return Error Code generated by function. 0 indicates no error.
1479 */
1480 virtual ctre::phoenix::ErrorCode Config_kD(int slotIdx, double value, int timeoutMs = 0);
1481 /**
1482 * Sets the 'F' constant in the given parameter slot.
1483 *
1484 * See documentation for calculation details.
1485 * If using velocity, motion magic, or motion profile,
1486 * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
1487 *
1488 * @param slotIdx
1489 * Parameter slot for the constant.
1490 * @param value
1491 * Value of the F constant.
1492 * @param timeoutMs
1493 * Timeout value in ms. If nonzero, function will wait for
1494 * config success and report an error if it times out.
1495 * If zero, no blocking or checking is performed.
1496 * @return Error Code generated by function. 0 indicates no error.
1497 */
1498 virtual ctre::phoenix::ErrorCode Config_kF(int slotIdx, double value, int timeoutMs = 0);
1499 /**
1500 * Sets the Integral Zone constant in the given parameter slot. If the
1501 * (absolute) closed-loop error is outside of this zone, integral
1502 * accumulator is automatically cleared. This ensures than integral wind up
1503 * events will stop after the sensor gets far enough from its target.
1504 *
1505 * @param slotIdx
1506 * Parameter slot for the constant.
1507 * @param izone
1508 * Value of the Integral Zone constant (closed loop error units X
1509 * 1ms).
1510 * @param timeoutMs
1511 * Timeout value in ms. If nonzero, function will wait for config
1512 * success and report an error if it times out. If zero, no
1513 * blocking or checking is performed.
1514 * @return Error Code generated by function. 0 indicates no error.
1515 */
1516 virtual ctre::phoenix::ErrorCode Config_IntegralZone(int slotIdx, double izone,
1517 int timeoutMs = 0);
1518 /**
1519 * Sets the allowable closed-loop error in the given parameter slot.
1520 *
1521 * @param slotIdx
1522 * Parameter slot for the constant.
1523 * @param allowableCloseLoopError
1524 * Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
1525 * @param timeoutMs
1526 * Timeout value in ms. If nonzero, function will wait for
1527 * config success and report an error if it times out.
1528 * If zero, no blocking or checking is performed.
1529 * @return Error Code generated by function. 0 indicates no error.
1530 */
1532 double allowableCloseLoopError, int timeoutMs = 0);
1533 /**
1534 * Sets the maximum integral accumulator in the given parameter slot.
1535 *
1536 * @param slotIdx
1537 * Parameter slot for the constant.
1538 * @param iaccum
1539 * Value of the maximum integral accumulator (closed loop error
1540 * units X 1ms).
1541 * @param timeoutMs
1542 * Timeout value in ms. If nonzero, function will wait for config
1543 * success and report an error if it times out. If zero, no
1544 * blocking or checking is performed.
1545 * @return Error Code generated by function. 0 indicates no error.
1546 */
1547 virtual ctre::phoenix::ErrorCode ConfigMaxIntegralAccumulator(int slotIdx, double iaccum,
1548 int timeoutMs = 0);
1549 /**
1550 * Sets the peak closed-loop output. This peak output is slot-specific and
1551 * is applied to the output of the associated PID loop.
1552 * This setting is seperate from the generic Peak Output setting.
1553 *
1554 * @param slotIdx
1555 * Parameter slot for the constant.
1556 * @param percentOut
1557 * Peak Percent Output from 0 to 1. This value is absolute and
1558 * the magnitude will apply in both forward and reverse directions.
1559 * @param timeoutMs
1560 * Timeout value in ms. If nonzero, function will wait for
1561 * config success and report an error if it times out.
1562 * If zero, no blocking or checking is performed.
1563 * @return Error Code generated by function. 0 indicates no error.
1564 */
1565 virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs = 0);
1566 /**
1567 * Sets the loop time (in milliseconds) of the PID closed-loop calculations.
1568 * Default value is 1 ms.
1569 *
1570 * @param slotIdx
1571 * Parameter slot for the constant.
1572 * @param loopTimeMs
1573 * Loop timing of the closed-loop calculations. Minimum value of
1574 * 1 ms, maximum of 64 ms.
1575 * @param timeoutMs
1576 * Timeout value in ms. If nonzero, function will wait for
1577 * config success and report an error if it times out.
1578 * If zero, no blocking or checking is performed.
1579 * @return Error Code generated by function. 0 indicates no error.
1580 */
1581 virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs = 0);
1582
1583 /**
1584 * Configures the Polarity of the Auxiliary PID (PID1).
1585 *
1586 * Standard Polarity:
1587 * Primary Output = PID0 + PID1,
1588 * Auxiliary Output = PID0 - PID1,
1589 *
1590 * Inverted Polarity:
1591 * Primary Output = PID0 - PID1,
1592 * Auxiliary Output = PID0 + PID1,
1593 *
1594 * @param invert
1595 * If true, use inverted PID1 output polarity.
1596 * @param timeoutMs
1597 * Timeout value in ms. If nonzero, function will wait for config
1598 * success and report an error if it times out. If zero, no
1599 * blocking or checking is performed.
1600 * @return Error Code
1601 */
1602 virtual ctre::phoenix::ErrorCode ConfigAuxPIDPolarity(bool invert, int timeoutMs = 0);
1603
1604 /**
1605 * Configures all slot persistant settings
1606 *
1607 * @param slot Object with all of the slot persistant settings
1608 * @param slotIdx Index of slot to configure
1609 * @param timeoutMs
1610 * Timeout value in ms. If nonzero, function will wait for
1611 * config success and report an error if it times out.
1612 * If zero, no blocking or checking is performed.
1613 *
1614 * @return Error Code generated by function. 0 indicates no error.
1615 */
1616 ctre::phoenix::ErrorCode ConfigureSlot(const SlotConfiguration& slot, int slotIdx, int timeoutMs);
1617
1618 //------ Close loop State ----------//
1619 /**
1620 * Sets the integral accumulator. Typically this is used to clear/zero the
1621 * integral accumulator, however some use cases may require seeding the
1622 * accumulator for a faster response.
1623 *
1624 * @param iaccum
1625 * Value to set for the integral accumulator (closed loop error
1626 * units X 1ms).
1627 * @param pidIdx
1628 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1629 * @param timeoutMs
1630 * Timeout value in ms. If nonzero, function will wait for config
1631 * success and report an error if it times out. If zero, no
1632 * blocking or checking is performed.
1633 * @return Error Code generated by function. 0 indicates no error.
1634 */
1635 virtual ctre::phoenix::ErrorCode SetIntegralAccumulator(double iaccum, int pidIdx = 0, int timeoutMs = 0);
1636 /**
1637 * Gets the closed-loop error. The units depend on which control mode is in
1638 * use.
1639 *
1640 * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
1641 * and current sensor value (in sensor units. Example 4096 units per rotation for CTRE Mag Encoder).
1642 *
1643 * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
1644 * and current sensor value (in sensor units per 100ms).
1645 *
1646 * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
1647 * and not the "final" target at the end of the profile/movement.
1648 *
1649 * See Phoenix-Documentation information on units.
1650 *
1651 * @param pidIdx
1652 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1653 * @return Closed-loop error value.
1654 */
1655 virtual double GetClosedLoopError(int pidIdx = 0);
1656 /**
1657 * Gets the iaccum value.
1658 *
1659 * @param pidIdx
1660 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1661 * @return Integral accumulator value (Closed-loop error X 1ms).
1662 */
1663 virtual double GetIntegralAccumulator(int pidIdx = 0);
1664 /**
1665 * Gets the derivative of the closed-loop error.
1666 *
1667 * @param pidIdx
1668 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1669 * @return The error derivative value.
1670 */
1671 virtual double GetErrorDerivative(int pidIdx = 0);
1672
1673 /**
1674 * Selects which profile slot to use for closed-loop control.
1675 *
1676 * @param slotIdx
1677 * Profile slot to select.
1678 * @param pidIdx
1679 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1680 **/
1681 virtual ctre::phoenix::ErrorCode SelectProfileSlot(int slotIdx, int pidIdx);
1682
1683 /**
1684 * Gets the current target of a given closed loop.
1685 *
1686 * @param pidIdx
1687 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1688 * @return The closed loop target.
1689 */
1690 virtual double GetClosedLoopTarget(int pidIdx = 0);
1691 /**
1692 * Gets the active trajectory target position using
1693 * MotionMagic/MotionProfile control modes.
1694 *
1695 * @return The Active Trajectory Position in sensor units.
1696 */ virtual double GetActiveTrajectoryPosition(int pidIdx = 0);
1697 /**
1698 * Gets the active trajectory target velocity using
1699 * MotionMagic/MotionProfile control modes.
1700 *
1701 * @return The Active Trajectory Velocity in sensor units per 100ms.
1702 */
1703 virtual double GetActiveTrajectoryVelocity(int pidIdx = 0); /**
1704 * Gets the active trajectory arbitrary feedforward using
1705 * MotionMagic/MotionProfile control modes.
1706 *
1707 * @param pidIdx
1708 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1709 * @return The Active Trajectory ArbFeedFwd in units of percent output
1710 * (where 0.01 is 1%).
1711 */
1712 virtual double GetActiveTrajectoryArbFeedFwd(int pidIdx = 0);
1713
1714 //------ Motion Profile Settings used in Motion Magic ----------//
1715 /**
1716 * Sets the Motion Magic Cruise Velocity. This is the peak target velocity
1717 * that the motion magic curve generator can use.
1718 *
1719 * @param sensorUnitsPer100ms
1720 * Motion Magic Cruise Velocity (in raw sensor units per 100 ms).
1721 * @param timeoutMs
1722 * Timeout value in ms. If nonzero, function will wait for config
1723 * success and report an error if it times out. If zero, no
1724 * blocking or checking is performed.
1725 * @return Error Code generated by function. 0 indicates no error.
1726 */
1727 virtual ctre::phoenix::ErrorCode ConfigMotionCruiseVelocity(double sensorUnitsPer100ms,
1728 int timeoutMs = 0);
1729 /**
1730 * Sets the Motion Magic Acceleration. This is the target acceleration that
1731 * the motion magic curve generator can use.
1732 *
1733 * @param sensorUnitsPer100msPerSec
1734 * Motion Magic Acceleration (in raw sensor units per 100 ms per
1735 * second).
1736 * @param timeoutMs
1737 * Timeout value in ms. If nonzero, function will wait for config
1738 * success and report an error if it times out. If zero, no
1739 * blocking or checking is performed.
1740 * @return Error Code generated by function. 0 indicates no error.
1741 */
1742 virtual ctre::phoenix::ErrorCode ConfigMotionAcceleration(double sensorUnitsPer100msPerSec,
1743 int timeoutMs = 0);
1744 /**
1745 * Sets the Motion Magic S Curve Strength.
1746 * Call this before using Motion Magic.
1747 * Modifying this during a Motion Magic action should be avoided.
1748 *
1749 * @param curveStrength
1750 * 0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing).
1751 * @param timeoutMs
1752 * Timeout value in ms. If nonzero, function will wait for config
1753 * success and report an error if it times out. If zero, no
1754 * blocking or checking is performed.
1755 * @return Error Code generated by function. 0 indicates no error.
1756 */
1757 virtual ctre::phoenix::ErrorCode ConfigMotionSCurveStrength(int curveStrength, int timeoutMs = 0);
1758 //------ Motion Profile Buffer ----------//
1759 /**
1760 * Clear the buffered motion profile in both controller's RAM (bottom), and in the
1761 * API (top).
1762 */
1764 /**
1765 * Retrieve just the buffer count for the api-level (top) buffer. This
1766 * routine performs no CAN or data structure lookups, so its fast and ideal
1767 * if caller needs to quickly poll the progress of trajectory points being
1768 * emptied into controller's RAM. Otherwise just use GetMotionProfileStatus.
1769 *
1770 * @return number of trajectory points in the top buffer.
1771 */
1773 /**
1774 * Push another trajectory point into the top level buffer (which is emptied
1775 * into the motor controller's bottom buffer as room allows).
1776 * @param trajPt to push into buffer.
1777 * The members should be filled in with these values...
1778 *
1779 * targPos: servo position in sensor units.
1780 * targVel: velocity to feed-forward in sensor units
1781 * per 100ms.
1782 * profileSlotSelect0 Which slot to get PIDF gains. PID is used for position servo. F is used
1783 * as the Kv constant for velocity feed-forward. Typically this is hardcoded
1784 * to the a particular slot, but you are free gain schedule if need be.
1785 * Choose from [0,3]
1786 * profileSlotSelect1 Which slot to get PIDF gains for auxiliary PId.
1787 * This only has impact during MotionProfileArc Control mode.
1788 * Choose from [0,1].
1789 * isLastPoint set to nonzero to signal motor controller to keep processing this
1790 * trajectory point, instead of jumping to the next one
1791 * when timeDurMs expires. Otherwise MP executer will
1792 * eventually see an empty buffer after the last point
1793 * expires, causing it to assert the IsUnderRun flag.
1794 * However this may be desired if calling application
1795 * never wants to terminate the MP.
1796 * zeroPos set to nonzero to signal motor controller to "zero" the selected
1797 * position sensor before executing this trajectory point.
1798 * Typically the first point should have this set only thus
1799 * allowing the remainder of the MP positions to be relative to
1800 * zero.
1801 * timeDur Duration to apply this trajectory pt.
1802 * This time unit is ADDED to the exising base time set by
1803 * configMotionProfileTrajectoryPeriod().
1804 * @return CTR_OKAY if trajectory point push ok. ErrorCode if buffer is
1805 * full due to kMotionProfileTopBufferCapacity.
1806 */
1808 /**
1809 * @brief Simple one-shot firing of a complete MP.
1810 * Starting in 2019, MPs can be fired by building a Buffered Trajectory Point Stream, and calling this routine.
1811 *
1812 * Once called, the motor controller software will automatically ...
1813 * [1] Clear the firmware buffer of trajectory points.
1814 * [2] Clear the underrun flags
1815 * [3] Reset an index within the Buffered Trajectory Point Stream (so that the same profile can be run again and again).
1816 * [4] Start a background thread to manage MP streaming (if not already running).
1817 * [5a] If current control mode already matches motionProfControlMode, set MPE Output to "Hold".
1818 * [5b] If current control mode does not matches motionProfControlMode, apply motionProfControlMode and set MPE Output to "Disable".
1819 * [6] Stream the trajectory points into the device's firmware buffer.
1820 * [7] Once motor controller has at least minBufferedPts worth in the firmware buffer, MP will automatically start (MPE Output set to "Enable").
1821 * [8] Wait until MP finishes, then transitions the Motion Profile Executor's output to "Hold".
1822 * [9] IsMotionProfileFinished() will now return true.
1823 *
1824 * Calling application can use IsMotionProfileFinished() to determine when internal state machine reaches [7].
1825 * Calling application can cancel MP by calling set(). Otherwise do not call set() until MP has completed.
1826 *
1827 * The legacy API from previous years requires the calling application to pass points via the ProcessMotionProfileBuffer and PushMotionProfileTrajectory.
1828 * This is no longer required if using this StartMotionProfile/IsMotionProfileFinished API.
1829 *
1830 * @param stream A buffer that will be used to stream the trajectory points. Caller can fill this container with the entire trajectory point, regardless of size.
1831 * @param minBufferedPts Minimum number of firmware buffered points before starting MP.
1832 * Do not exceed device's firmware buffer capacity or MP will never fire (120 for Motion Profile, or 60 for Motion Profile Arc).
1833 * Recommendation value for this would be five to ten samples depending on timeDur of the trajectory point.
1834 * @param motionProfControlMode Pass MotionProfile or MotionProfileArc.
1835 * @return nonzero error code if operation fails.
1836 */
1838 /**
1839 * @brief Determine if running MP is complete.
1840 * This requires using the StartMotionProfile routine to start the MP.
1841 * That is because managing the trajectory points is now done in a background thread (if StartMotionProfile is called).
1842 *
1843 * If calling application uses the legacy API (more-complex buffering API) from previous years, than this API will
1844 * not return true.
1845 *
1846 * @return true if MP was started using StartMotionProfile, and it has completed execution (MPE is now in "hold").
1847 */
1849 /**
1850 * Retrieve just the buffer full for the api-level (top) buffer. This
1851 * routine performs no CAN or data structure lookups, so its fast and ideal
1852 * if caller needs to quickly poll. Otherwise just use
1853 * GetMotionProfileStatus.
1854 *
1855 * @return number of trajectory points in the top buffer.
1856 */
1858 /**
1859 * This must be called periodically to funnel the trajectory points from the
1860 * API's top level buffer to the controller's bottom level buffer. Recommendation
1861 * is to call this twice as fast as the execution rate of the motion
1862 * profile. So if MP is running with 20ms trajectory points, try calling
1863 * this routine every 10ms. All motion profile functions are thread-safe
1864 * through the use of a mutex, so there is no harm in having the caller
1865 * utilize threading.
1866 */
1868 /**
1869 * Retrieve all status information.
1870 * For best performance, Caller can snapshot all status information regarding the
1871 * motion profile executer.
1872 *
1873 * @param statusToFill Caller supplied object to fill.
1874 *
1875 * The members are filled, as follows...
1876 *
1877 * topBufferRem: The available empty slots in the trajectory buffer.
1878 * The robot API holds a "top buffer" of trajectory points, so your applicaion
1879 * can dump several points at once. The API will then stream them into the
1880 * low-level buffer, allowing the motor controller to act on them.
1881 *
1882 * topBufferRem: The number of points in the top trajectory buffer.
1883 *
1884 * btmBufferCnt: The number of points in the low level controller buffer.
1885 *
1886 * hasUnderrun: Set if isUnderrun ever gets set.
1887 * Can be manually cleared by ClearMotionProfileHasUnderrun() or automatically cleared by StartMotionProfile().
1888 *
1889 * isUnderrun: This is set if controller needs to shift a point from its buffer into
1890 * the active trajectory point however
1891 * the buffer is empty.
1892 * This gets cleared automatically when is resolved.
1893 *
1894 * activePointValid: True if the active trajectory point is not empty, false otherwise. The members in activePoint are only valid if this signal is set.
1895 *
1896 * isLast: is set/cleared based on the MP executer's current
1897 * trajectory point's IsLast value. This assumes
1898 * IsLast was set when PushMotionProfileTrajectory
1899 * was used to insert the currently processed trajectory
1900 * point.
1901 *
1902 * profileSlotSelect: The currently processed trajectory point's
1903 * selected slot. This can differ in the currently selected slot used
1904 * for Position and Velocity servo modes
1905 *
1906 * outputEnable: The current output mode of the motion profile
1907 * executer (disabled, enabled, or hold). When changing the set()
1908 * value in MP mode, it's important to check this signal to
1909 * confirm the change takes effect before interacting with the top buffer.
1910 */
1912 /**
1913 * Clear the "Has Underrun" flag. Typically this is called after application
1914 * has confirmed an underrun had occured.
1915 *
1916 * @param timeoutMs
1917 * Timeout value in ms. If nonzero, function will wait for config
1918 * success and report an error if it times out. If zero, no
1919 * blocking or checking is performed.
1920 * @return Error Code generated by function. 0 indicates no error.
1921 */
1923 /**
1924 * Calling application can opt to speed up the handshaking between the robot
1925 * API and the controller to increase the download rate of the controller's Motion
1926 * Profile. Ideally the period should be no more than half the period of a
1927 * trajectory point.
1928 *
1929 * @param periodMs
1930 * The transmit period in ms.
1931 * @return Error Code generated by function. 0 indicates no error.
1932 */
1934 /**
1935 * When trajectory points are processed in the motion profile executer, the MPE determines
1936 * how long to apply the active trajectory point by summing baseTrajDurationMs with the
1937 * timeDur of the trajectory point (see TrajectoryPoint).
1938 *
1939 * This allows general selection of the execution rate of the points with 1ms resolution,
1940 * while allowing some degree of change from point to point.
1941 * @param baseTrajDurationMs The base duration time of every trajectory point.
1942 * This is summed with the trajectory points unique timeDur.
1943 * @param timeoutMs
1944 * Timeout value in ms. If nonzero, function will wait for
1945 * config success and report an error if it times out.
1946 * If zero, no blocking or checking is performed.
1947 * @return Error Code generated by function. 0 indicates no error.
1948 */
1949 virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryPeriod(int baseTrajDurationMs, int timeoutMs = 0);
1950 /**
1951 * When trajectory points are processed in the buffer, the motor controller can
1952 * linearly interpolate additional trajectory points between the buffered
1953 * points. The time delta between these interpolated points is 1 ms.
1954 *
1955 * By default this feature is enabled.
1956 *
1957 * @param enable Whether to enable the trajectory point interpolation feature.
1958 * @param timeoutMs
1959 * Timeout value in ms. If nonzero, function will wait for
1960 * config success and report an error if it times out.
1961 * If zero, no blocking or checking is performed.
1962 * @return Error Code generated by function. 0 indicates no error.
1963 */
1965
1966
1967 //------Feedback Device Interaction Settings---------//
1968 /**
1969 * Disables continuous tracking of the position for analog and pulse-width.
1970 * If the signal goes from 4095 to 0 (pulse-width) a motor controller will continue to read 4096 by default.
1971 * If overflow tracking is disabled, it will wrap to 0 (not continuous)
1972 *
1973 * If using pulse-width on CTRE Mag Encoder (within one rotation) or absolute analog sensor (within one rotation),
1974 * setting feedbackNotContinuous to true is recommended, to prevent intermittent
1975 * connections from causing sensor "jumps" of 4096 (or 1024 for analog) units.
1976 *
1977 * @param feedbackNotContinuous True to disable the overflow tracking.
1978 *
1979 * @param timeoutMs
1980 * Timeout value in ms. If nonzero, function will wait for
1981 * config success and report an error if it times out.
1982 * If zero, no blocking or checking is performed.
1983 * @return Error Code generated by function. 0 indicates no error.
1984 */
1985 virtual ErrorCode ConfigFeedbackNotContinuous(bool feedbackNotContinuous, int timeoutMs = 0);
1986 /**
1987 * Disables going to neutral (brake/coast) when a remote sensor is no longer detected.
1988 *
1989 * @param remoteSensorClosedLoopDisableNeutralOnLOS disable going to neutral
1990 *
1991 * @param timeoutMs
1992 * Timeout value in ms. If nonzero, function will wait for
1993 * config success and report an error if it times out.
1994 * If zero, no blocking or checking is performed.
1995 * @return Error Code generated by function. 0 indicates no error.
1996 */
1997 virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs = 0);
1998 /**
1999 * Enables clearing the position of the feedback sensor when the forward
2000 * limit switch is triggered
2001 *
2002 * @param clearPositionOnLimitF Whether clearing is enabled, defaults false
2003 * @param timeoutMs
2004 * Timeout value in ms. If nonzero, function will wait for
2005 * config success and report an error if it times out.
2006 * If zero, no blocking or checking is performed.
2007 * @return Error Code generated by function. 0 indicates no error.
2008 */
2009 virtual ErrorCode ConfigClearPositionOnLimitF(bool clearPositionOnLimitF, int timeoutMs = 0);
2010 /**
2011 * Enables clearing the position of the feedback sensor when the reverse
2012 * limit switch is triggered
2013 *
2014 * @param clearPositionOnLimitR Whether clearing is enabled, defaults false
2015 * @param timeoutMs
2016 * Timeout value in ms. If nonzero, function will wait for
2017 * config success and report an error if it times out.
2018 * If zero, no blocking or checking is performed.
2019 * @return Error Code generated by function. 0 indicates no error.
2020 */
2021 virtual ErrorCode ConfigClearPositionOnLimitR(bool clearPositionOnLimitR, int timeoutMs = 0);
2022 /**
2023 * Enables clearing the position of the feedback sensor when the quadrature index signal
2024 * is detected
2025 *
2026 * @param clearPositionOnQuadIdx Whether clearing is enabled, defaults false
2027 * @param timeoutMs
2028 * Timeout value in ms. If nonzero, function will wait for
2029 * config success and report an error if it times out.
2030 * If zero, no blocking or checking is performed.
2031 * @return Error Code generated by function. 0 indicates no error.
2032 */
2033 virtual ErrorCode ConfigClearPositionOnQuadIdx(bool clearPositionOnQuadIdx, int timeoutMs = 0);
2034 /**
2035 * Disables limit switches triggering (if enabled) when the sensor is no longer detected.
2036 *
2037 * @param limitSwitchDisableNeutralOnLOS disable triggering
2038 *
2039 * @param timeoutMs
2040 * Timeout value in ms. If nonzero, function will wait for
2041 * config success and report an error if it times out.
2042 * If zero, no blocking or checking is performed.
2043 * @return Error Code generated by function. 0 indicates no error.
2044 */
2045 virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS(bool limitSwitchDisableNeutralOnLOS, int timeoutMs = 0);
2046 /**
2047 * Disables soft limits triggering (if enabled) when the sensor is no longer detected.
2048 *
2049 * @param softLimitDisableNeutralOnLOS disable triggering
2050 *
2051 * @param timeoutMs
2052 * Timeout value in ms. If nonzero, function will wait for
2053 * config success and report an error if it times out.
2054 * If zero, no blocking or checking is performed.
2055 * @return Error Code generated by function. 0 indicates no error.
2056 */
2057 virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS(bool softLimitDisableNeutralOnLOS, int timeoutMs = 0);
2058 /**
2059 * Sets the edges per rotation of a pulse width sensor. (This should be set for
2060 * tachometer use).
2061 *
2062 * @param pulseWidthPeriod_EdgesPerRot edges per rotation
2063 *
2064 * @param timeoutMs
2065 * Timeout value in ms. If nonzero, function will wait for
2066 * config success and report an error if it times out.
2067 * If zero, no blocking or checking is performed.
2068 * @return Error Code generated by function. 0 indicates no error.
2069 */
2070 virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs = 0);
2071 /**
2072 * Sets the number of samples to use in smoothing a pulse width sensor with a rolling
2073 * average. Default is 1 (no smoothing).
2074 *
2075 * @param pulseWidthPeriod_FilterWindowSz samples for rolling avg
2076 *
2077 * @param timeoutMs
2078 * Timeout value in ms. If nonzero, function will wait for
2079 * config success and report an error if it times out.
2080 * If zero, no blocking or checking is performed.
2081 * @return Error Code generated by function. 0 indicates no error.
2082 */
2083 virtual ErrorCode ConfigPulseWidthPeriod_FilterWindowSz(int pulseWidthPeriod_FilterWindowSz, int timeoutMs = 0);
2084
2085 //------ error ----------//
2086 /**
2087 * Gets the last error generated by this object. Not all functions return an
2088 * error code but can potentially report errors. This function can be used
2089 * to retrieve those error codes.
2090 *
2091 * @return Last Error Code generated by a function.
2092 */
2094 //------ Faults ----------//
2095 /**
2096 * Polls the various fault flags.
2097 *
2098 * @param toFill
2099 * Caller's object to fill with latest fault flags.
2100 * @return Last Error Code generated by a function.
2101 */
2103 /**
2104 * Polls the various sticky fault flags.
2105 *
2106 * @param toFill
2107 * Caller's object to fill with latest sticky fault flags.
2108 * @return Last Error Code generated by a function.
2109 */
2111 /**
2112 * Clears all sticky faults.
2113 *
2114 * @param timeoutMs
2115 * Timeout value in ms. If nonzero, function will wait for config
2116 * success and report an error if it times out. If zero, no
2117 * blocking or checking is performed.
2118 * @return Last Error Code generated by a function.
2119 */
2121 //------ Firmware ----------//
2122 /**
2123 * Gets the firmware version of the device.
2124 *
2125 * @return Firmware version of device. For example: version 1-dot-2 is
2126 * 0x0102.
2127 */
2128 virtual int GetFirmwareVersion();
2129 /**
2130 * Returns true if the device has reset since last call.
2131 *
2132 * @return Has a Device Reset Occurred?
2133 */
2134 virtual bool HasResetOccurred();
2135 //------ Custom Persistent Params ----------//
2136 /**
2137 * Sets the value of a custom parameter. This is for arbitrary use.
2138 *
2139 * Sometimes it is necessary to save calibration/limit/target information in
2140 * the device. Particularly if the device is part of a subsystem that can be
2141 * replaced.
2142 *
2143 * @param newValue
2144 * Value for custom parameter.
2145 * @param paramIndex
2146 * Index of custom parameter [0,1]
2147 * @param timeoutMs
2148 * Timeout value in ms. If nonzero, function will wait for config
2149 * success and report an error if it times out. If zero, no
2150 * blocking or checking is performed.
2151 * @return Error Code generated by function. 0 indicates no error.
2152 */
2153 virtual ctre::phoenix::ErrorCode ConfigSetCustomParam(int newValue, int paramIndex,
2154 int timeoutMs = 0);
2155 /**
2156 * Gets the value of a custom parameter.
2157 *
2158 * @param paramIndex
2159 * Index of custom parameter [0,1].
2160 * @param timeoutMs
2161 * Timeout value in ms. If nonzero, function will wait for config
2162 * success and report an error if it times out. If zero, no
2163 * blocking or checking is performed.
2164 * @return Value of the custom param.
2165 */
2166 virtual int ConfigGetCustomParam(int paramIndex,
2167 int timeoutMs = 0);
2168 //------ Generic Param API, typically not used ----------//
2169 /**
2170 * Sets a parameter. Generally this is not used. This can be utilized in -
2171 * Using new features without updating API installation. - Errata
2172 * workarounds to circumvent API implementation. - Allows for rapid testing
2173 * / unit testing of firmware.
2174 *
2175 * @param param
2176 * Parameter enumeration.
2177 * @param value
2178 * Value of parameter.
2179 * @param subValue
2180 * Subvalue for parameter. Maximum value of 255.
2181 * @param ordinal
2182 * Ordinal of parameter.
2183 * @param timeoutMs
2184 * Timeout value in ms. If nonzero, function will wait for config
2185 * success and report an error if it times out. If zero, no
2186 * blocking or checking is performed.
2187 * @return Error Code generated by function. 0 indicates no error.
2188 */
2190 uint8_t subValue, int ordinal, int timeoutMs = 0);
2191 /**
2192 * Gets a parameter.
2193 *
2194 * @param param
2195 * Parameter enumeration.
2196 * @param ordinal
2197 * Ordinal of parameter.
2198 * @param timeoutMs
2199 * Timeout value in ms. If nonzero, function will wait for
2200 * config success and report an error if it times out.
2201 * If zero, no blocking or checking is performed.
2202 * @return Value of parameter.
2203 */
2204 virtual double ConfigGetParameter(ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs = 0);
2205 /**
2206 * Gets a parameter by passing an int by reference
2207 *
2208 * @param param
2209 * Parameter enumeration
2210 * @param valueToSend
2211 * Value to send to parameter
2212 * @param valueReceived
2213 * Reference to integer to receive
2214 * @param subValue
2215 * SubValue of parameter
2216 * @param ordinal
2217 * Ordinal of parameter
2218 * @param timeoutMs
2219 * Timeout value in ms. If nonzero, function will wait for
2220 * config success and report an error if it times out.
2221 * If zero, no blocking or checking is performed.
2222 * @return Error Code generated by function. 0 indicates no error.
2223 */
2224 virtual ErrorCode ConfigGetParameter(ParamEnum param, int32_t valueToSend,
2225 int32_t& valueReceived, uint8_t& subValue, int32_t ordinal,
2226 int32_t timeoutMs);
2227 //------ Misc. ----------//
2228 virtual int GetBaseID();
2229 /**
2230 * @return control mode motor controller is in
2231 */
2233 // ----- Follower ------//
2234 /**
2235 * Set the control mode and output value so that this motor controller will
2236 * follow another motor controller. Currently supports following Victor SPX,
2237 * Talon SRX, and Talon FX.
2238 *
2239 * @param masterToFollow
2240 * Motor Controller object to follow.
2241 * @param followerType
2242 * Type of following control. Use AuxOutput1 to follow the master
2243 * device's auxiliary output 1.
2244 * Use PercentOutput for standard follower mode.
2245 */
2247 /**
2248 * Set the control mode and output value so that this motor controller will
2249 * follow another motor controller. Currently supports following Victor SPX,
2250 * Talon SRX, and Talon FX.
2251 */
2252 virtual void Follow(IMotorController& masterToFollow);
2253 /**
2254 * When master makes a device, this routine is called to signal the update.
2255 */
2256 virtual void ValueUpdated();
2257
2258
2259 //-------Config All----------//
2260 /**
2261 * Gets all slot persistant settings.
2262 *
2263 * @param slot Object with all of the slot persistant settings
2264 * @param slotIdx Parameter slot for the constant.
2265 * @param timeoutMs
2266 * Timeout value in ms. If nonzero, function will wait for
2267 * config success and report an error if it times out.
2268 * If zero, no blocking or checking is performed.
2269 */
2270 void GetSlotConfigs(SlotConfiguration& slot, int slotIdx = 0, int timeoutMs = 50);
2271 /**
2272 * Gets all filter persistant settings.
2273 *
2274 * @param Filter Object with all of the filter persistant settings
2275 * @param ordinal 0 for remote sensor 0 and 1 for remote sensor 1.
2276 * @param timeoutMs
2277 * Timeout value in ms. If nonzero, function will wait for
2278 * config success and report an error if it times out.
2279 * If zero, no blocking or checking is performed.
2280 */
2281 void GetFilterConfigs(FilterConfiguration& Filter, int ordinal = 0, int timeoutMs = 50);
2282
2283 /**
2284 * @return CCI handle for child classes.
2285 */
2286 void* GetHandle();
2287
2288 };// class BaseMotorController
2289 } // namespace can
2290 } // namespace motorcontrol
2291 } // namespace phoenix
2292} // namespace ctre
Stream of trajectory points for Talon/Victor motion profiling.
Definition: BufferedTrajectoryPointStream.h:13
Interface for motor controllers.
Definition: IMotorController.h:35
static std::string toString(RemoteSensorSource value)
Get string representation of specified remote sensor source.
Definition: RemoteSensorSource.h:101
Collection of simulation commands available to a VictorSPX motor controller.
Definition: VictorSPXSimCollection.h:26
Base motor controller features for all CTRE CAN motor controllers.
Definition: BaseMotorController.h:578
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementWindow(int windowSize, int timeoutMs=0)
Sets the number of velocity samples used in the rolling average velocity measurement.
virtual void NeutralOutput()
Neutral the motor output by setting control mode to disabled.
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs=0)
Sets the peak closed-loop output.
virtual ctre::phoenix::ErrorCode ChangeMotionControlFramePeriod(int periodMs)
Calling application can opt to speed up the handshaking between the robot API and the controller to i...
virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::motorcontrol::can::BaseTalon &talonRef, int remoteOrdinal, int timeoutMs=0)
Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
virtual ErrorCode ConfigClearPositionOnQuadIdx(bool clearPositionOnQuadIdx, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the quadrature index signal is detected.
ctre::phoenix::ErrorCode ConfigureSlot(const SlotConfiguration &slot, int slotIdx, int timeoutMs)
Configures all slot persistant settings.
virtual ctre::phoenix::ErrorCode SelectProfileSlot(int slotIdx, int pidIdx)
Selects which profile slot to use for closed-loop control.
virtual ctre::phoenix::ErrorCode ClearStickyFaults(int timeoutMs=0)
Clears all sticky faults.
virtual void EnableVoltageCompensation(bool enable)
Enables voltage compensation.
virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS(bool limitSwitchDisableNeutralOnLOS, int timeoutMs=0)
Disables limit switches triggering (if enabled) when the sensor is no longer detected.
virtual ctre::phoenix::ErrorCode ConfigVoltageMeasurementFilter(int filterWindowSamples, int timeoutMs=0)
Configures the voltage measurement filter.
virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::sensors::CANCoder &canCoderRef, int remoteOrdinal, int timeoutMs=0)
Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
virtual void OverrideSoftLimitsEnable(bool enable)
Can be used to override-disable the soft limits.
virtual double GetSelectedSensorPosition(int pidIdx=0)
Get the selected sensor position (in raw sensor units).
virtual ctre::phoenix::ErrorCode ConfigSensorTerm(SensorTerm sensorTerm, FeedbackDevice feedbackDevice, int timeoutMs=0)
Select what sensor term should be bound to switch feedback device.
virtual ErrorCode ConfigGetParameter(ParamEnum param, int32_t valueToSend, int32_t &valueReceived, uint8_t &subValue, int32_t ordinal, int32_t timeoutMs)
Gets a parameter by passing an int by reference.
virtual ctre::phoenix::ErrorCode Config_kP(int slotIdx, double value, int timeoutMs=0)
Sets the 'P' constant in the given parameter slot.
virtual double GetIntegralAccumulator(int pidIdx=0)
Gets the iaccum value.
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitEnable(bool enable, int timeoutMs=0)
Configures the reverse soft limit enable.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
virtual bool IsVoltageCompensationEnabled()
Returns the enable state of Voltage Compensation that the caller has set.
virtual ctre::phoenix::ErrorCode BaseConfigAllSettings(const BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
Configures all base persistant settings.
virtual ctre::phoenix::ErrorCode ConfigAllowableClosedloopError(int slotIdx, double allowableCloseLoopError, int timeoutMs=0)
Sets the allowable closed-loop error in the given parameter slot.
virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs=0)
Sets the edges per rotation of a pulse width sensor.
virtual void SetInverted(bool invert)
Inverts the hbridge output of the motor controller.
virtual double GetSelectedSensorVelocity(int pidIdx=0)
Get the selected sensor velocity.
virtual double GetMotorOutputPercent()
Gets the output percentage of the motor controller.
virtual ctre::phoenix::ErrorCode Config_kI(int slotIdx, double value, int timeoutMs=0)
Sets the 'I' constant in the given parameter slot.
virtual ErrorCode ConfigFeedbackNotContinuous(bool feedbackNotContinuous, int timeoutMs=0)
Disables continuous tracking of the position for analog and pulse-width.
virtual ctre::phoenix::ErrorCode ConfigMotionCruiseVelocity(double sensorUnitsPer100ms, int timeoutMs=0)
Sets the Motion Magic Cruise Velocity.
virtual double GetTemperature()
Gets the temperature of the motor controller.
virtual double GetClosedLoopTarget(int pidIdx=0)
Gets the current target of a given closed loop.
virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs=0)
Sets the loop time (in milliseconds) of the PID closed-loop calculations.
virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS(bool softLimitDisableNeutralOnLOS, int timeoutMs=0)
Disables soft limits triggering (if enabled) when the sensor is no longer detected.
virtual int GetFirmwareVersion()
Gets the firmware version of the device.
virtual double GetBusVoltage()
Gets the bus voltage seen by the device.
virtual ErrorCode ConfigClearPositionOnLimitR(bool clearPositionOnLimitR, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the reverse limit switch is triggered.
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitThreshold(double forwardSensorLimit, int timeoutMs=0)
Configures the forward soft limit threhold.
virtual void SetNeutralMode(NeutralMode neutralMode)
Sets the mode of operation during neutral throttle output.
virtual ctre::phoenix::ErrorCode PushMotionProfileTrajectory(const ctre::phoenix::motion::TrajectoryPoint &trajPt)
Push another trajectory point into the top level buffer (which is emptied into the motor controller's...
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the feedback device for the motor controller.
virtual ctre::phoenix::ErrorCode ConfigMotionSCurveStrength(int curveStrength, int timeoutMs=0)
Sets the Motion Magic S Curve Strength.
virtual ctre::phoenix::ErrorCode Config_kF(int slotIdx, double value, int timeoutMs=0)
Sets the 'F' constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode ClearMotionProfileHasUnderrun(int timeoutMs=0)
Clear the "Has Underrun" flag.
virtual ctre::phoenix::ErrorCode ConfigMaxIntegralAccumulator(int slotIdx, double iaccum, int timeoutMs=0)
Sets the maximum integral accumulator in the given parameter slot.
virtual ctre::phoenix::ErrorCode ConfigNeutralDeadband(double percentDeadband, int timeoutMs=0)
Configures the output deadband percentage.
virtual double GetClosedLoopError(int pidIdx=0)
Gets the closed-loop error.
virtual ctre::phoenix::ErrorCode ConfigFactoryDefault(int timeoutMs=50)
Revert all configurations to factory default values.
virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs=0)
Disables going to neutral (brake/coast) when a remote sensor is no longer detected.
virtual double GetActiveTrajectoryVelocity(int pidIdx=0)
Gets the active trajectory target velocity using MotionMagic/MotionProfile control modes.
virtual void SetSensorPhase(bool PhaseSensor)
Sets the phase of the sensor.
virtual int GetDeviceID()
Returns the Device ID.
virtual double GetOutputCurrent()
Gets the output current of the motor controller.
BaseMotorController & operator=(BaseMotorController const &)=delete
virtual ctre::phoenix::ErrorCode ConfigNominalOutputForward(double percentOut, int timeoutMs=0)
Configures the forward nominal output percentage.
static void DestroyAllMotControllers()
Destructs all motor controller objects.
virtual ctre::phoenix::ErrorCode ConfigNominalOutputReverse(double percentOut, int timeoutMs=0)
Configures the reverse nominal output percentage.
void Follow(IMotorController &masterToFollow, ctre::phoenix::motorcontrol::FollowerType followerType)
Set the control mode and output value so that this motor controller will follow another motor control...
virtual void BaseGetPIDConfigs(BasePIDSetConfiguration &pid, int pidIdx, int timeoutMs)
Gets all base PID set persistant settings.
virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual ctre::phoenix::ErrorCode ConfigPeakOutputForward(double percentOut, int timeoutMs=0)
Configures the forward peak output percentage.
virtual ctre::phoenix::ErrorCode StartMotionProfile(ctre::phoenix::motion::BufferedTrajectoryPointStream &stream, uint32_t minBufferedPts, ControlMode motionProfControlMode)
Simple one-shot firing of a complete MP.
virtual ctre::phoenix::ErrorCode ConfigReverseSoftLimitThreshold(double reverseSensorLimit, int timeoutMs=0)
Configures the reverse soft limit threshold.
virtual ctre::phoenix::ErrorCode ConfigPeakOutputReverse(double percentOut, int timeoutMs=0)
Configures the reverse peak output percentage.
virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1)
virtual ctre::phoenix::ErrorCode ConfigRemoteFeedbackFilter(int deviceID, RemoteSensorSource remoteSensorSource, int remoteOrdinal, int timeoutMs=0)
Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
virtual ctre::phoenix::ErrorCode ConfigAuxPIDPolarity(bool invert, int timeoutMs=0)
Configures the Polarity of the Auxiliary PID (PID1).
virtual bool IsMotionProfileTopLevelBufferFull()
Retrieve just the buffer full for the api-level (top) buffer.
virtual ErrorCode ConfigClearPositionOnLimitF(bool clearPositionOnLimitF, int timeoutMs=0)
Enables clearing the position of the feedback sensor when the forward limit switch is triggered.
virtual ctre::phoenix::ErrorCode ConfigClosedloopRamp(double secondsFromNeutralToFull, int timeoutMs=0)
Configures the closed-loop ramp rate of throttle output.
virtual void SetInverted(InvertType invertType)
Inverts the hbridge output of the motor controller in relation to the master if present.
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrame frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
virtual ErrorCode ConfigPulseWidthPeriod_FilterWindowSz(int pulseWidthPeriod_FilterWindowSz, int timeoutMs=0)
Sets the number of samples to use in smoothing a pulse width sensor with a rolling average.
virtual double ConfigGetParameter(ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs=0)
Gets a parameter.
virtual int ConfigGetCustomParam(int paramIndex, int timeoutMs=0)
Gets the value of a custom parameter.
void GetFilterConfigs(FilterConfiguration &Filter, int ordinal=0, int timeoutMs=50)
Gets all filter persistant settings.
virtual ctre::phoenix::ErrorCode ConfigSensorTerm(SensorTerm sensorTerm, RemoteFeedbackDevice feedbackDevice, int timeoutMs=0)
Select what sensor term should be bound to switch feedback device.
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
virtual ctre::phoenix::ErrorCode GetLastError()
Gets the last error generated by this object.
virtual ctre::phoenix::ErrorCode SetStatusFramePeriod(StatusFrameEnhanced frame, uint8_t periodMs, int timeoutMs=0)
Sets the period of the given status frame.
virtual bool IsMotionProfileFinished()
Determine if running MP is complete.
virtual ctre::phoenix::ErrorCode ConfigSetCustomParam(int newValue, int paramIndex, int timeoutMs=0)
Sets the value of a custom parameter.
virtual ctre::phoenix::ErrorCode GetMotionProfileStatus(ctre::phoenix::motion::MotionProfileStatus &statusToFill)
Retrieve all status information.
virtual ctre::phoenix::ErrorCode ConfigMotionAcceleration(double sensorUnitsPer100msPerSec, int timeoutMs=0)
Sets the Motion Magic Acceleration.
virtual void BaseGetAllConfigs(BaseMotorControllerConfiguration &allConfigs, int timeoutMs)
Gets all base persistant settings.
virtual void Follow(IMotorController &masterToFollow)
Set the control mode and output value so that this motor controller will follow another motor control...
void GetSlotConfigs(SlotConfiguration &slot, int slotIdx=0, int timeoutMs=50)
Gets all slot persistant settings.
virtual ctre::phoenix::ErrorCode SetIntegralAccumulator(double iaccum, int pidIdx=0, int timeoutMs=0)
Sets the integral accumulator.
virtual void ValueUpdated()
When master makes a device, this routine is called to signal the update.
virtual ctre::phoenix::ErrorCode ConfigOpenloopRamp(double secondsFromNeutralToFull, int timeoutMs=0)
Configures the open-loop ramp rate of throttle output.
virtual ctre::phoenix::ErrorCode GetFaults(Faults &toFill)
Polls the various fault flags.
virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryInterpolationEnable(bool enable, int timeoutMs=0)
When trajectory points are processed in the buffer, the motor controller can linearly interpolate add...
virtual ctre::phoenix::ErrorCode ConfigForwardSoftLimitEnable(bool enable, int timeoutMs=0)
Configures the forward soft limit enable.
virtual ctre::phoenix::ErrorCode ConfigSetParameter(ctre::phoenix::ParamEnum param, double value, uint8_t subValue, int ordinal, int timeoutMs=0)
Sets a parameter.
virtual ctre::phoenix::ErrorCode ConfigReverseLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures the reverse limit switch for a remote source.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackCoefficient(double coefficient, int pidIdx=0, int timeoutMs=0)
The Feedback Coefficient is a scalar applied to the value of the feedback sensor.
virtual ErrorCode ClearMotionProfileTrajectories()
Clear the buffered motion profile in both controller's RAM (bottom), and in the API (top).
virtual ctre::phoenix::ErrorCode ConfigVoltageCompSaturation(double voltage, int timeoutMs=0)
Configures the Voltage Compensation saturation voltage.
virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryPeriod(int baseTrajDurationMs, int timeoutMs=0)
When trajectory points are processed in the motion profile executer, the MPE determines how long to a...
virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs=0)
Gets the period of the given status frame.
virtual double GetActiveTrajectoryArbFeedFwd(int pidIdx=0)
Gets the active trajectory arbitrary feedforward using MotionMagic/MotionProfile control modes.
virtual int GetMotionProfileTopLevelBufferCount()
Retrieve just the buffer count for the api-level (top) buffer.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(VelocityMeasPeriod period, int timeoutMs=0)
ctre::phoenix::motorcontrol::VictorSPXSimCollection & GetVictorSPXSimCollection()
Definition: BaseMotorController.h:599
virtual bool HasResetOccurred()
Returns true if the device has reset since last call.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int deviceID, int timeoutMs=0)
Configures the forward limit switch for a remote source.
BaseMotorController(BaseMotorController const &)=delete
virtual ctre::phoenix::ErrorCode Config_IntegralZone(int slotIdx, double izone, int timeoutMs=0)
Sets the Integral Zone constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode GetStickyFaults(StickyFaults &toFill)
Polls the various sticky fault flags.
virtual ctre::phoenix::ErrorCode SetControlFramePeriod(ControlFrame frame, int periodMs)
Sets the period of the given control frame.
virtual void ProcessMotionProfileBuffer()
This must be called periodically to funnel the trajectory points from the API's top level buffer to t...
virtual double GetActiveTrajectoryPosition(int pidIdx=0)
Gets the active trajectory target position using MotionMagic/MotionProfile control modes.
virtual ctre::phoenix::ErrorCode Config_kD(int slotIdx, double value, int timeoutMs=0)
Sets the 'D' constant in the given parameter slot.
virtual ctre::phoenix::ErrorCode ConfigVelocityMeasurementPeriod(ctre::phoenix::sensors::SensorVelocityMeasPeriod period, int timeoutMs=0)
Sets the period over which velocity measurements are taken.
void OverrideLimitSwitchesEnable(bool enable)
Sets the enable state for limit switches.
virtual void Set(ControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
virtual ctre::phoenix::ErrorCode ConfigForwardLimitSwitchSource(LimitSwitchSource type, LimitSwitchNormal normalOpenOrClose, int timeoutMs=0)
Configures a limit switch for a local/remote source.
BaseMotorController(int deviceNumber, const char *model, std::string const &canbus="")
Constructor for motor controllers.
virtual double GetErrorDerivative(int pidIdx=0)
Gets the derivative of the closed-loop error.
virtual ctre::phoenix::ErrorCode SetSelectedSensorPosition(double sensorPos, int pidIdx=0, int timeoutMs=50)
Sets the sensor position to the given value.
Util class to help with Base Motor Controller configs.
Definition: BaseMotorController.h:533
static bool PeakOutputReverseDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:546
static bool ClearPositionOnLimitFDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:565
static bool ReverseSoftLimitEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:557
static bool ForwardSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:554
static bool VoltageCompSaturationDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:550
static bool VoltageMeasurementFilterDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:551
static bool MotionCruiseVelocityDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:559
static bool MotionAccelerationDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:560
static bool PulseWidthPeriod_FilterWindowSzDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:571
static bool OpenloopRampDifferent(const BaseMotorControllerConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:543
static bool AuxPIDPolarityDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:558
static bool FeedbackNotContinuousDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:563
static bool TrajectoryInterpolationEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:572
static bool PeakOutputForwardDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:545
static bool VelocityMeasurementWindowDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:553
static bool MotionProfileTrajectoryPeriodDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:562
static bool ClosedloopRampDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:544
static bool ReverseSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:555
static bool NominalOutputReverseDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:548
static bool NeutralDeadbandDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:549
static bool MotionSCurveStrength(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:561
static bool ForwardSoftLimitEnableDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:556
static bool PulseWidthPeriod_EdgesPerRotDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:570
static bool RemoteSensorClosedLoopDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:564
static bool ClearPositionOnLimitRDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:566
static bool SoftLimitDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:569
static bool VelocityMeasurementPeriodDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:552
static bool ClearPositionOnQuadIdxDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:567
static bool NominalOutputForwardDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:547
static bool LimitSwitchDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration &settings)
Definition: BaseMotorController.h:568
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: BaseTalon.h:267
Util Class to help with slot configs.
Definition: BaseMotorController.h:250
static bool KPDifferent(const SlotConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:260
static bool KFDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:263
static bool ClosedLoopPeriodDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:268
static bool KDDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:262
static bool MaxIntegralAccumulatorDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:266
static bool KIDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:261
static bool ClosedLoopPeakOutputDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:267
static bool IntegralZoneDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:264
static bool AllowableClosedloopErrorDifferent(const SlotConfiguration &settings)
Definition: BaseMotorController.h:265
CTRE CANCoder.
Definition: CANCoder.h:233
static std::string toString(SensorVelocityMeasPeriod value)
String representation of specified CANCoderVelocityMeasPeriod.
Definition: SensorVelocityMeasPeriod.h:58
ControlMode
Choose the control mode for a motor controller.
Definition: ControlMode.h:11
@ PercentOutput
Percent output [-1,1].
FollowerType
Choose the type of follower.
Definition: FollowerType.h:11
DemandType
How to interpret a demand value.
Definition: DemandType.h:10
InvertType
Choose the invert type of the motor controller.
Definition: InvertType.h:14
@ None
Same as SetInverted(false)
StatusFrameEnhanced
The different status frames available to enhanced motor controllers.
Definition: StatusFrame.h:11
SensorTerm
Choose the sensor term for a motor controller.
Definition: SensorTerm.h:11
LimitSwitchNormal
Choose whether the limit switch is normally open or normally closed.
Definition: LimitSwitchType.h:62
RemoteSensorSource
Choose the remote sensor source for a motor controller.
Definition: RemoteSensorSource.h:13
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
NeutralMode
Choose the neutral mode for a motor controller.
Definition: NeutralMode.h:11
ControlFrame
Control Frames for motor controllers.
Definition: ControlFrame.h:11
VelocityMeasPeriod
Velocity Measurement Periods.
Definition: VelocityMeasPeriod.h:13
@ Period_100Ms
100ms measurement period
Definition: VelocityMeasPeriod.h:45
StatusFrame
The different status frames available to motor controllers.
Definition: StatusFrame.h:99
LimitSwitchSource
Limit switch source enum.
Definition: LimitSwitchType.h:11
SensorVelocityMeasPeriod
Enumerate filter periods for any sensor that measures velocity.
Definition: SensorVelocityMeasPeriod.h:13
ParamEnum
Signal enumeration for generic signal access.
Definition: paramEnum.h:13
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
Util class to help custom configs.
Definition: CustomParamConfiguration.h:53
Configurables for any custom param configs.
Definition: CustomParamConfiguration.h:11
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
std::string toString()
Definition: CustomParamConfiguration.h:34
Motion Profile Status This is simply a data transer object.
Definition: MotionProfileStatus.h:15
Motion Profile Trajectory Point This is simply a data transfer object.
Definition: TrajectoryPoint.h:11
All the faults available to motor controllers.
Definition: Faults.h:11
All the sticky faults available to motor controllers.
Definition: StickyFaults.h:11
Configurables available to base motor controllers.
Definition: BaseMotorController.h:276
double motionCruiseVelocity
Motion Magic cruise velocity in raw sensor units per 100 ms.
Definition: BaseMotorController.h:379
int motionCurveStrength
Zero to use trapezoidal motion during motion magic.
Definition: BaseMotorController.h:387
bool auxPIDPolarity
PID polarity inversion.
Definition: BaseMotorController.h:367
bool clearPositionOnQuadIdx
Clear the position on index.
Definition: BaseMotorController.h:414
double motionAcceleration
Motion Magic acceleration in (raw sensor units per 100 ms) per second.
Definition: BaseMotorController.h:383
SlotConfiguration slot3
Configuration for slot 3.
Definition: BaseMotorController.h:355
bool clearPositionOnLimitR
Clear the position on reverse limit.
Definition: BaseMotorController.h:410
double nominalOutputReverse
Nominal/Minimum output in reverse direction [-1,0].
Definition: BaseMotorController.h:300
double openloopRamp
Seconds to go from 0 to full in open loop.
Definition: BaseMotorController.h:280
int pulseWidthPeriod_FilterWindowSz
Desired window size for a tachometer sensor.
Definition: BaseMotorController.h:430
double voltageCompSaturation
This is the max voltage to apply to the hbridge when voltage compensation is enabled.
Definition: BaseMotorController.h:311
double neutralDeadband
Neutral deadband [0.001, 0.25].
Definition: BaseMotorController.h:304
bool remoteSensorClosedLoopDisableNeutralOnLOS
Disable neutral'ing the motor when remote sensor is lost on CAN bus.
Definition: BaseMotorController.h:402
double closedloopRamp
Seconds to go from 0 to full in closed loop.
Definition: BaseMotorController.h:284
double reverseSoftLimitThreshold
Threshold for soft limits in reverse direction (in raw sensor units)
Definition: BaseMotorController.h:331
int pulseWidthPeriod_EdgesPerRot
Number of edges per rotation for a tachometer sensor.
Definition: BaseMotorController.h:426
bool softLimitDisableNeutralOnLOS
Disable neutral'ing the motor when remote soft limit is lost on CAN bus.
Definition: BaseMotorController.h:422
std::string toString(std::string prependString)
Definition: BaseMotorController.h:483
double peakOutputForward
Peak output in forward direction [0,1].
Definition: BaseMotorController.h:288
int velocityMeasurementWindow
Desired window for velocity measurement.
Definition: BaseMotorController.h:323
bool forwardSoftLimitEnable
Enable forward soft limit.
Definition: BaseMotorController.h:335
SlotConfiguration slot0
Configuration for slot 0.
Definition: BaseMotorController.h:343
int motionProfileTrajectoryPeriod
Motion profile base trajectory period in milliseconds.
Definition: BaseMotorController.h:394
bool feedbackNotContinuous
Determine whether feedback sensor is continuous or not.
Definition: BaseMotorController.h:398
FilterConfiguration remoteFilter1
Configuration for RemoteFilter 1.
Definition: BaseMotorController.h:375
int voltageMeasurementFilter
Number of samples in rolling average for voltage.
Definition: BaseMotorController.h:315
bool trajectoryInterpolationEnable
Enable motion profile trajectory point interpolation (defaults to true).
Definition: BaseMotorController.h:434
SlotConfiguration slot2
Configuration for slot 2.
Definition: BaseMotorController.h:351
ctre::phoenix::sensors::SensorVelocityMeasPeriod velocityMeasurementPeriod
Desired period for velocity measurement.
Definition: BaseMotorController.h:319
bool reverseSoftLimitEnable
Enable reverse soft limit.
Definition: BaseMotorController.h:339
FilterConfiguration remoteFilter0
Configuration for RemoteFilter 0.
Definition: BaseMotorController.h:371
BaseMotorControllerConfiguration()
Definition: BaseMotorController.h:436
bool clearPositionOnLimitF
Clear the position on forward limit.
Definition: BaseMotorController.h:406
bool limitSwitchDisableNeutralOnLOS
Disable neutral'ing the motor when remote limit switch is lost on CAN bus.
Definition: BaseMotorController.h:418
double nominalOutputForward
Nominal/Minimum output in forward direction [0,1].
Definition: BaseMotorController.h:296
std::string toString()
Definition: BaseMotorController.h:474
double peakOutputReverse
Peak output in reverse direction [-1,0].
Definition: BaseMotorController.h:292
SlotConfiguration slot1
Configuration for slot 1.
Definition: BaseMotorController.h:347
double forwardSoftLimitThreshold
Threshold for soft limits in forward direction (in raw sensor units)
Definition: BaseMotorController.h:327
Base set of configurables related to PID.
Definition: BaseMotorController.h:50
BasePIDSetConfiguration()
Definition: BaseMotorController.h:57
double selectedFeedbackCoefficient
Feedback coefficient of selected sensor.
Definition: BaseMotorController.h:55
std::string toString()
Definition: BaseMotorController.h:65
std::string toString(const std::string &prependString)
Definition: BaseMotorController.h:74
Util class to help with filter configs.
Definition: BaseMotorController.h:123
static bool RemoteSensorSourceDifferent(const FilterConfiguration &settings)
Definition: BaseMotorController.h:134
static bool RemoteSensorDeviceIDDifferent(const FilterConfiguration &settings)
Determine if specified value is different from default.
Definition: BaseMotorController.h:133
static bool FilterConfigurationDifferent(const FilterConfiguration &settings)
Definition: BaseMotorController.h:135
Configurations for filters.
Definition: BaseMotorController.h:83
std::string toString(std::string prependString)
Definition: BaseMotorController.h:111
std::string toString()
Definition: BaseMotorController.h:103
FilterConfiguration()
Definition: BaseMotorController.h:94
int remoteSensorDeviceID
Remote Sensor's device ID.
Definition: BaseMotorController.h:88
RemoteSensorSource remoteSensorSource
The remote sensor device and signal type to bind.
Definition: BaseMotorController.h:92
Configurables available to a slot.
Definition: BaseMotorController.h:142
double maxIntegralAccumulator
Max integral accumulator (in native units)
Definition: BaseMotorController.h:194
std::string toString(std::string prependString)
Definition: BaseMotorController.h:229
double allowableClosedloopError
Allowable closed loop error to neutral (in native units)
Definition: BaseMotorController.h:190
double kD
D Gain.
Definition: BaseMotorController.h:168
int closedLoopPeriod
Desired period of closed loop [1,64]ms.
Definition: BaseMotorController.h:202
SlotConfiguration()
Definition: BaseMotorController.h:204
std::string toString()
Definition: BaseMotorController.h:220
double kI
I Gain.
Definition: BaseMotorController.h:160
double kP
P Gain.
Definition: BaseMotorController.h:151
double kF
F Gain.
Definition: BaseMotorController.h:177
double closedLoopPeakOutput
Peak output from closed loop [0,1].
Definition: BaseMotorController.h:198
double integralZone
Integral zone (in native units)
Definition: BaseMotorController.h:185