CTRE Phoenix C++ 5.35.1
Loading...
Searching...
No Matches
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
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
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 const 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 const 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
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 const 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; }
551 static bool VoltageMeasurementFilterDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.voltageMeasurementFilter == _default().voltageMeasurementFilter)) || !settings.enableOptimizations; }
552 static bool VelocityMeasurementPeriodDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.velocityMeasurementPeriod == _default().velocityMeasurementPeriod)) || !settings.enableOptimizations; }
553 static bool VelocityMeasurementWindowDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.velocityMeasurementWindow == _default().velocityMeasurementWindow)) || !settings.enableOptimizations; }
554 static bool ForwardSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.forwardSoftLimitThreshold == _default().forwardSoftLimitThreshold)) || !settings.enableOptimizations; }
555 static bool ReverseSoftLimitThresholdDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.reverseSoftLimitThreshold == _default().reverseSoftLimitThreshold)) || !settings.enableOptimizations; }
556 static bool ForwardSoftLimitEnableDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.forwardSoftLimitEnable == _default().forwardSoftLimitEnable)) || !settings.enableOptimizations; }
557 static bool ReverseSoftLimitEnableDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.reverseSoftLimitEnable == _default().reverseSoftLimitEnable)) || !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; }
562 static bool MotionProfileTrajectoryPeriodDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.motionProfileTrajectoryPeriod == _default().motionProfileTrajectoryPeriod)) || !settings.enableOptimizations; }
563 static bool FeedbackNotContinuousDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.feedbackNotContinuous == _default().feedbackNotContinuous)) || !settings.enableOptimizations; }
564 static bool RemoteSensorClosedLoopDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.remoteSensorClosedLoopDisableNeutralOnLOS == _default().remoteSensorClosedLoopDisableNeutralOnLOS)) || !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; }
567 static bool ClearPositionOnQuadIdxDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.clearPositionOnQuadIdx == _default().clearPositionOnQuadIdx)) || !settings.enableOptimizations; }
568 static bool LimitSwitchDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.limitSwitchDisableNeutralOnLOS == _default().limitSwitchDisableNeutralOnLOS)) || !settings.enableOptimizations; }
569 static bool SoftLimitDisableNeutralOnLOSDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.softLimitDisableNeutralOnLOS == _default().softLimitDisableNeutralOnLOS)) || !settings.enableOptimizations; }
570 static bool PulseWidthPeriod_EdgesPerRotDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.pulseWidthPeriod_EdgesPerRot == _default().pulseWidthPeriod_EdgesPerRot)) || !settings.enableOptimizations; }
571 static bool PulseWidthPeriod_FilterWindowSzDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.pulseWidthPeriod_FilterWindowSz == _default().pulseWidthPeriod_FilterWindowSz)) || !settings.enableOptimizations; }
572 static bool TrajectoryInterpolationEnableDifferent(const BaseMotorControllerConfiguration& settings) { return (!(settings.trajectoryInterpolationEnable == _default().trajectoryInterpolationEnable)) || !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 *
640 * [[deprecated("Use GetStatorCurrent/GetSupplyCurrent instead.")]]
641 *
642 * @return The output current (in amps).
643 */
644 virtual double GetOutputCurrent();
645
646 public:
647 /**
648 * Constructor for motor controllers.
649 *
650 * @param arbId Device ID [0,62]
651 * @param model String model of device.
652 * Examples: "Talon SRX", "Talon FX", "Victor SPX".
653 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
654 * or a CANivore device name or serial number
655 */
656 BaseMotorController(int deviceNumber, const char* model, std::string const &canbus = "");
661
662 /**
663 * Destructs all motor controller objects
664 */
666
667 /**
668 * Returns the Device ID
669 *
670 * @return Device number.
671 */
672 virtual int GetDeviceID();
673 // ------ Set output routines. ----------//
674 /**
675 * Sets the appropriate output on the talon, depending on the mode.
676 * @param mode The output mode to apply.
677 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
678 * In Current mode, output value is in amperes.
679 * In Velocity mode, output value is in position change / 100ms.
680 * In Position mode, output value is in encoder ticks or an analog value,
681 * depending on the sensor.
682 * In Follower mode, the output value is the integer device ID of the talon to
683 * duplicate.
684 *
685 * @param value The setpoint value, as described above.
686 *
687 *
688 * Standard Driving Example:
689 * _talonLeft.set(ControlMode.PercentOutput, leftJoy);
690 * _talonRght.set(ControlMode.PercentOutput, rghtJoy);
691 */
692 virtual void Set(ControlMode mode, double value);
693 /**
694 * @param mode Sets the appropriate output on the talon, depending on the mode.
695 * @param demand0 The output value to apply.
696 * such as advanced feed forward and/or auxiliary close-looping in firmware.
697 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
698 * In Current mode, output value is in amperes.
699 * In Velocity mode, output value is in position change / 100ms.
700 * In Position mode, output value is in encoder ticks or an analog value,
701 * depending on the sensor. See
702 * In Follower mode, the output value is the integer device ID of the talon to
703 * duplicate.
704 *
705 * @param demand1Type The demand type for demand1.
706 * Neutral: Ignore demand1 and apply no change to the demand0 output.
707 * AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary
708 * PID is always executed as standard Position PID control.
709 * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
710 * demand0 output. In PercentOutput the demand0 output is the motor output,
711 * and in closed-loop modes the demand0 output is the output of PID0.
712 * @param demand1 Supplmental output value.
713 * AuxPID: Target position in Sensor Units
714 * ArbitraryFeedForward: Percent Output between -1.0 and 1.0
715 *
716 *
717 * Arcade Drive Example:
718 * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
719 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
720 *
721 * Drive Straight Example:
722 * Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
723 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
724 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
725 *
726 * Drive Straight to a Distance Example:
727 * Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
728 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
729 * _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
730 */
731 virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1);
732 /**
733 * Neutral the motor output by setting control mode to disabled.
734 */
735 virtual void NeutralOutput();
736 /**
737 * Sets the mode of operation during neutral throttle output.
738 *
739 * @param neutralMode
740 * The desired mode of operation when the Controller output
741 * throttle is neutral (ie brake/coast)
742 **/
743 virtual void SetNeutralMode(NeutralMode neutralMode);
744 //------ Invert behavior ----------//
745 /**
746 * Sets the phase of the sensor. Use when controller forward/reverse output
747 * doesn't correlate to appropriate forward/reverse reading of sensor.
748 * Pick a value so that positive PercentOutput yields a positive change in sensor.
749 * After setting this, user can freely call SetInverted() with any value.
750 *
751 * @param PhaseSensor
752 * Indicates whether to invert the phase of the sensor.
753 */
754 virtual void SetSensorPhase(bool PhaseSensor);
755 /**
756 * Inverts the hbridge output of the motor controller.
757 *
758 * This does not impact sensor phase and should not be used to correct sensor polarity.
759 *
760 * This will invert the hbridge output but NOT the LEDs.
761 * This ensures....
762 * - Green LEDs always represents positive request from robot-controller/closed-looping mode.
763 * - Green LEDs correlates to forward limit switch.
764 * - Green LEDs correlates to forward soft limit.
765 *
766 * @param invert
767 * Invert state to set.
768 */
769 virtual void SetInverted(bool invert);
770 /**
771 * Inverts the hbridge output of the motor controller in relation to the master if present
772 *
773 * This does not impact sensor phase and should not be used to correct sensor polarity.
774 *
775 * This will allow you to either:
776 * - Not invert the motor
777 * - Invert the motor
778 * - Always follow the master regardless of master's inversion
779 * - Always oppose the master regardless of master's inversion
780 *
781 * @param invertType
782 * Invert state to set.
783 */
784 virtual void SetInverted(InvertType invertType);
785 /**
786 * @return invert setting of motor output.
787 */
788 virtual bool GetInverted() const;
789 //----- Factory Default Configuration -----//
790 /**
791 * Revert all configurations to factory default values.
792 * Use this before your individual config* calls to avoid having to config every single param.
793 *
794 * Alternatively you can use the configAllSettings routine.
795 *
796 * @param timeoutMs
797 * Timeout value in ms. Function will generate error if config is
798 * not successful within timeout.
799 * @return Error Code generated by function. 0 indicates no error.
800 */
802 //----- general output shaping ------------------//
803 /**
804 * Configures the open-loop ramp rate of throttle output.
805 *
806 * @param secondsFromNeutralToFull
807 * Minimum desired time to go from neutral to full throttle. A
808 * value of '0' will disable the ramp.
809 * @param timeoutMs
810 * Timeout value in ms. If nonzero, function will wait for
811 * config success and report an error if it times out.
812 * If zero, no blocking or checking is performed.
813 * @return Error Code generated by function. 0 indicates no error.
814 */
815 virtual ctre::phoenix::ErrorCode ConfigOpenloopRamp(double secondsFromNeutralToFull,
816 int timeoutMs = 0);
817 /**
818 * Configures the closed-loop ramp rate of throttle output.
819 *
820 * @param secondsFromNeutralToFull
821 * Minimum desired time to go from neutral to full throttle. A
822 * value of '0' will disable the ramp.
823 * @param timeoutMs
824 * Timeout value in ms. If nonzero, function will wait for
825 * config success and report an error if it times out.
826 * If zero, no blocking or checking is performed.
827 * @return Error Code generated by function. 0 indicates no error.
828 */
829 virtual ctre::phoenix::ErrorCode ConfigClosedloopRamp(double secondsFromNeutralToFull,
830 int timeoutMs = 0);
831 /**
832 * Configures the forward peak output percentage.
833 *
834 * @param percentOut
835 * Desired peak output percentage. [0,1]
836 * @param timeoutMs
837 * Timeout value in ms. If nonzero, function will wait for
838 * config success and report an error if it times out.
839 * If zero, no blocking or checking is performed.
840 * @return Error Code generated by function. 0 indicates no error.
841 */
842 virtual ctre::phoenix::ErrorCode ConfigPeakOutputForward(double percentOut, int timeoutMs = 0);
843 /**
844 * Configures the reverse peak output percentage.
845 *
846 * @param percentOut
847 * Desired peak output percentage.
848 * @param timeoutMs
849 * Timeout value in ms. If nonzero, function will wait for
850 * config success and report an error if it times out.
851 * If zero, no blocking or checking is performed.
852 * @return Error Code generated by function. 0 indicates no error.
853 */
854 virtual ctre::phoenix::ErrorCode ConfigPeakOutputReverse(double percentOut, int timeoutMs = 0);
855 /**
856 * Configures the forward nominal output percentage.
857 *
858 * @param percentOut
859 * Nominal (minimum) percent output. [0,+1]
860 * @param timeoutMs
861 * Timeout value in ms. If nonzero, function will wait for
862 * config success and report an error if it times out.
863 * If zero, no blocking or checking is performed.
864 * @return Error Code generated by function. 0 indicates no error.
865 */
867 int timeoutMs = 0);
868 /**
869 * Configures the reverse nominal output percentage.
870 *
871 * @param percentOut
872 * Nominal (minimum) percent output. [-1,0]
873 * @param timeoutMs
874 * Timeout value in ms. If nonzero, function will wait for
875 * config success and report an error if it times out.
876 * If zero, no blocking or checking is performed.
877 * @return Error Code generated by function. 0 indicates no error.
878 */
880 int timeoutMs = 0);
881 /**
882 * Configures the output deadband percentage.
883 *
884 * @param percentDeadband
885 * Desired deadband percentage. Minimum is 0.1%, Maximum is 25%.
886 * Pass 0.04 for 4% (factory default).
887 * @param timeoutMs
888 * Timeout value in ms. If nonzero, function will wait for
889 * config success and report an error if it times out.
890 * If zero, no blocking or checking is performed.
891 * @return Error Code generated by function. 0 indicates no error.
892 */
893 virtual ctre::phoenix::ErrorCode ConfigNeutralDeadband(double percentDeadband,
894 int timeoutMs = 0);
895 //------ Voltage Compensation ----------//
896 /**
897 * Configures the Voltage Compensation saturation voltage.
898 *
899 * @param voltage
900 * This is the max voltage to apply to the hbridge when voltage
901 * compensation is enabled. For example, if 10 (volts) is specified
902 * and a TalonSRX is commanded to 0.5 (PercentOutput, closed-loop, etc)
903 * then the TalonSRX will attempt to apply a duty-cycle to produce 5V.
904 * @param timeoutMs
905 * Timeout value in ms. If nonzero, function will wait for
906 * config success and report an error if it times out.
907 * If zero, no blocking or checking is performed.
908 * @return Error Code generated by function. 0 indicates no error.
909 */
910 virtual ctre::phoenix::ErrorCode ConfigVoltageCompSaturation(double voltage, int timeoutMs = 0);
911 /**
912 * Configures the voltage measurement filter.
913 *
914 * @param filterWindowSamples
915 * Number of samples in the rolling average of voltage
916 * measurement.
917 * @param timeoutMs
918 * Timeout value in ms. If nonzero, function will wait for
919 * config success and report an error if it times out.
920 * If zero, no blocking or checking is performed.
921 * @return Error Code generated by function. 0 indicates no error.
922 */
924 int timeoutMs = 0);
925 /**
926 * Enables voltage compensation. If enabled, voltage compensation works in
927 * all control modes.
928 *
929 * Be sure to configure the saturation voltage before enabling this.
930 *
931 * @param enable
932 * Enable state of voltage compensation.
933 **/
934 virtual void EnableVoltageCompensation(bool enable);
935 /**
936 * Returns the enable state of Voltage Compensation that the caller has set.
937 *
938 * @return TRUE if voltage compensation is enabled.
939 */
941
942 //------ General Status ----------//
943 /**
944 * Gets the bus voltage seen by the device.
945 *
946 * @return The bus voltage value (in volts).
947 */
948 virtual double GetBusVoltage();
949 /**
950 * Gets the output percentage of the motor controller.
951 *
952 * @return Output of the motor controller (in percent).
953 */
954 virtual double GetMotorOutputPercent();
955 /**
956 * @return applied voltage to motor in volts.
957 */
958 virtual double GetMotorOutputVoltage();
959 /**
960 * Gets the temperature of the motor controller.
961 *
962 * @return Temperature of the motor controller (in 'C)
963 */
964 virtual double GetTemperature();
965
966 //------ sensor selection ----------//
967 /**
968 * Select the remote feedback device for the motor controller.
969 * Most CTRE CAN motor controllers will support remote sensors over CAN.
970 *
971 * @param feedbackDevice
972 * Remote Feedback Device to select.
973 * @param pidIdx
974 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
975 * @param timeoutMs
976 * Timeout value in ms. If nonzero, function will wait for
977 * config success and report an error if it times out.
978 * If zero, no blocking or checking is performed.
979 * @return Error Code generated by function. 0 indicates no error.
980 */
982 RemoteFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
983 /**
984 * Select the feedback device for the motor controller.
985 *
986 * @param feedbackDevice
987 * Feedback Device to select.
988 * @param pidIdx
989 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
990 * @param timeoutMs
991 * Timeout value in ms. If nonzero, function will wait for
992 * config success and report an error if it times out.
993 * If zero, no blocking or checking is performed.
994 * @return Error Code generated by function. 0 indicates no error.
995 */
997 FeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
998 /**
999 * The Feedback Coefficient is a scalar applied to the value of the
1000 * feedback sensor. Useful when you need to scale your sensor values
1001 * within the closed-loop calculations. Default value is 1.
1002 *
1003 * Selected Feedback Sensor register in firmware is the decoded sensor value
1004 * multiplied by the Feedback Coefficient.
1005 *
1006 * @param coefficient
1007 * Feedback Coefficient value. Maximum value of 1.
1008 * Resolution is 1/(2^16). Cannot be 0.
1009 * @param pidIdx
1010 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1011 * @param timeoutMs
1012 * Timeout value in ms. If nonzero, function will wait for
1013 * config success and report an error if it times out.
1014 * If zero, no blocking or checking is performed.
1015 * @return Error Code generated by function. 0 indicates no error.
1016 */
1018 double coefficient, int pidIdx = 0, int timeoutMs = 0);
1019 /**
1020 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1021 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1022 * as a PID source for closed-loop features.
1023 *
1024 * @param deviceID
1025 * The device ID of the remote sensor device.
1026 * @param remoteSensorSource
1027 * The remote sensor device and signal type to bind.
1028 * @param remoteOrdinal
1029 * 0 for configuring Remote Sensor 0,
1030 * 1 for configuring Remote Sensor 1
1031 * @param timeoutMs
1032 * Timeout value in ms. If nonzero, function will wait for
1033 * config success and report an error if it times out.
1034 * If zero, no blocking or checking is performed.
1035 * @return Error Code generated by function. 0 indicates no error.
1036 */
1038 RemoteSensorSource remoteSensorSource, int remoteOrdinal,
1039 int timeoutMs = 0);
1040 /**
1041 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1042 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1043 * as a PID source for closed-loop features.
1044 *
1045 * @param canCoderRef
1046 * CANCoder device reference to use.
1047 * @param remoteOrdinal
1048 * 0 for configuring Remote Sensor 0,
1049 * 1 for configuring Remote Sensor 1
1050 * @param timeoutMs
1051 * Timeout value in ms. If nonzero, function will wait for
1052 * config success and report an error if it times out.
1053 * If zero, no blocking or checking is performed.
1054 * @return Error Code generated by function. 0 indicates no error.
1055 */
1056 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
1057 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
1058 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
1059 virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::sensors::CANCoder &canCoderRef, int remoteOrdinal, int timeoutMs = 0);
1060 /**
1061 * Select what remote device and signal to assign to Remote Sensor 0 or Remote Sensor 1.
1062 * After binding a remote device and signal to Remote Sensor X, you may select Remote Sensor X
1063 * as a PID source for closed-loop features.
1064 *
1065 * @param talonRef
1066 * Talon device reference to use.
1067 * @param remoteOrdinal
1068 * 0 for configuring Remote Sensor 0,
1069 * 1 for configuring Remote Sensor 1
1070 * @param timeoutMs
1071 * Timeout value in ms. If nonzero, function will wait for
1072 * config success and report an error if it times out.
1073 * If zero, no blocking or checking is performed.
1074 * @return Error Code generated by function. 0 indicates no error.
1075 */
1076 virtual ErrorCode ConfigRemoteFeedbackFilter(ctre::phoenix::motorcontrol::can::BaseTalon &talonRef, int remoteOrdinal, int timeoutMs = 0);
1077 /**
1078 * Select what sensor term should be bound to switch feedback device.
1079 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
1080 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
1081 * The four terms are specified with this routine. Then Sensor Sum/Difference
1082 * can be selected for closed-looping.
1083 *
1084 * @param sensorTerm Which sensor term to bind to a feedback source.
1085 * @param feedbackDevice The sensor signal to attach to sensorTerm.
1086 * @param timeoutMs
1087 * Timeout value in ms. If nonzero, function will wait for
1088 * config success and report an error if it times out.
1089 * If zero, no blocking or checking is performed.
1090 * @return Error Code generated by function. 0 indicates no error.
1091 */
1093 FeedbackDevice feedbackDevice, int timeoutMs = 0);
1094 /**
1095 * Select what sensor term should be bound to switch feedback device.
1096 * Sensor Sum = Sensor Sum Term 0 - Sensor Sum Term 1
1097 * Sensor Difference = Sensor Diff Term 0 - Sensor Diff Term 1
1098 * The four terms are specified with this routine. Then Sensor Sum/Difference
1099 * can be selected for closed-looping.
1100 *
1101 * @param sensorTerm Which sensor term to bind to a feedback source.
1102 * @param feedbackDevice The sensor signal to attach to sensorTerm.
1103 * @param timeoutMs
1104 * Timeout value in ms. If nonzero, function will wait for
1105 * config success and report an error if it times out.
1106 * If zero, no blocking or checking is performed.
1107 * @return Error Code generated by function. 0 indicates no error.
1108 */
1110 RemoteFeedbackDevice feedbackDevice, int timeoutMs = 0);
1111
1112 //------- sensor status --------- //
1113 /**
1114 * Get the selected sensor position (in raw sensor units).
1115 *
1116 * @param pidIdx
1117 * 0 for Primary closed-loop. 1 for auxiliary closed-loop. See
1118 * Phoenix-Documentation for how to interpret.
1119 *
1120 * @return Position of selected sensor (in raw sensor units).
1121 */
1122 virtual double GetSelectedSensorPosition(int pidIdx = 0);
1123 /**
1124 * Get the selected sensor velocity.
1125 *
1126 * @param pidIdx
1127 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1128 * @return selected sensor (in raw sensor units) per 100ms.
1129 * See Phoenix-Documentation for how to interpret.
1130 */
1131 virtual double GetSelectedSensorVelocity(int pidIdx = 0);
1132 /**
1133 * Sets the sensor position to the given value.
1134 *
1135 * @param sensorPos
1136 * Position to set for the selected sensor (in raw sensor units).
1137 * @param pidIdx
1138 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1139 * @param timeoutMs
1140 * Timeout value in ms. If nonzero, function will wait for
1141 * config success and report an error if it times out.
1142 * If zero, no blocking or checking is performed.
1143 * @return Error Code generated by function. 0 indicates no error.
1144 */
1145 virtual ctre::phoenix::ErrorCode SetSelectedSensorPosition(double sensorPos, int pidIdx = 0, int timeoutMs = 50);
1146 //------ status frame period changes ----------//
1147 /**
1148 * Sets the period of the given control frame.
1149 *
1150 * @param frame
1151 * Frame whose period is to be changed.
1152 * @param periodMs
1153 * Period in ms for the given frame.
1154 * @return Error Code generated by function. 0 indicates no error.
1155 */
1157 /**
1158 * Sets the period of the given status frame.
1159 *
1160 * User ensure CAN Bus utilization is not high.
1161 *
1162 * This setting is not persistent and is lost when device is reset. If this
1163 * is a concern, calling application can use HasResetOccurred() to determine if the
1164 * status frame needs to be reconfigured.
1165 *
1166 * @param frame
1167 * Frame whose period is to be changed.
1168 * @param periodMs
1169 * Period in ms for the given frame.
1170 * @param timeoutMs
1171 * Timeout value in ms. If nonzero, function will wait for config
1172 * success and report an error if it times out. If zero, no
1173 * blocking or checking is performed.
1174 * @return Error Code generated by function. 0 indicates no error.
1175 */
1177 int timeoutMs = 0);
1178 /**
1179 * Sets the period of the given status frame.
1180 *
1181 * User ensure CAN Bus utilization is not high.
1182 *
1183 * This setting is not persistent and is lost when device is reset. If this
1184 * is a concern, calling application can use HasResetOccurred() to determine if the
1185 * status frame needs to be reconfigured.
1186 *
1187 * @param frame
1188 * Frame whose period is to be changed.
1189 * @param periodMs
1190 * Period in ms for the given frame.
1191 * @param timeoutMs
1192 * Timeout value in ms. If nonzero, function will wait for config
1193 * success and report an error if it times out. If zero, no
1194 * blocking or checking is performed.
1195 * @return Error Code generated by function. 0 indicates no error.
1196 */
1198 uint8_t periodMs, int timeoutMs = 0);
1199 /**
1200 * Gets the period of the given status frame.
1201 *
1202 * @param frame
1203 * Frame to get the period of.
1204 * @param timeoutMs
1205 * Timeout value in ms. If nonzero, function will wait for
1206 * config success and report an error if it times out.
1207 * If zero, no blocking or checking is performed.
1208 * @return Period of the given status frame.
1209 */
1210 virtual int GetStatusFramePeriod(StatusFrame frame, int timeoutMs = 0);
1211 /**
1212 * Gets the period of the given status frame.
1213 *
1214 * @param frame
1215 * Frame to get the period of.
1216 * @param timeoutMs
1217 * Timeout value in ms. If nonzero, function will wait for
1218 * config success and report an error if it times out.
1219 * If zero, no blocking or checking is performed.
1220 * @return Period of the given status frame.
1221 */
1222 virtual int GetStatusFramePeriod(StatusFrameEnhanced frame, int timeoutMs = 0);
1223 //----- velocity signal conditionaing ------//
1224 /**
1225 * Sets the period over which velocity measurements are taken.
1226 *
1227 * @param period
1228 * Desired period for the velocity measurement. @see
1229 * #SensorVelocityMeasPeriod
1230 * @param timeoutMs
1231 * Timeout value in ms. If nonzero, function will wait for
1232 * config success and report an error if it times out.
1233 * If zero, no blocking or checking is performed.
1234 * @return Error Code generated by function. 0 indicates no error.
1235 */
1237 int timeoutMs = 0);
1238
1239 [[deprecated("Use the overload with SensorVelocityMeasPeriod instead.")]]
1241 int timeoutMs = 0);
1242 /**
1243 * Sets the number of velocity samples used in the rolling average velocity
1244 * measurement.
1245 *
1246 * @param windowSize
1247 * Number of samples in the rolling average of velocity
1248 * measurement. Valid values are 1,2,4,8,16,32. If another value
1249 * is specified, it will truncate to nearest support value.
1250 * @param timeoutMs
1251 * Timeout value in ms. If nonzero, function will wait for config
1252 * success and report an error if it times out. If zero, no
1253 * blocking or checking is performed.
1254 * @return Error Code generated by function. 0 indicates no error.
1255 */
1257 int timeoutMs = 0);
1258 //------ remote limit switch ----------//
1259 /**
1260 * Configures the forward limit switch for a remote source. For example, a
1261 * CAN motor controller may need to monitor the Limit-F pin of another Talon
1262 * or CANifier.
1263 *
1264 * @param type
1265 * Remote limit switch source. User can choose between a remote
1266 * Talon SRX, CANifier, or deactivate the feature.
1267 * @param normalOpenOrClose
1268 * Setting for normally open, normally closed, or disabled. This
1269 * setting matches the Phoenix Tuner drop down.
1270 * @param deviceID
1271 * Device ID of remote source (Talon SRX or CANifier device ID).
1272 * @param timeoutMs
1273 * Timeout value in ms. If nonzero, function will wait for config
1274 * success and report an error if it times out. If zero, no
1275 * blocking or checking is performed.
1276 * @return Error Code generated by function. 0 indicates no error.
1277 */
1279 RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1280 int deviceID, int timeoutMs = 0);
1281 /**
1282 * Configures the reverse limit switch for a remote source. For example, a
1283 * CAN motor controller may need to monitor the Limit-R pin of another Talon
1284 * or CANifier.
1285 *
1286 * @param type
1287 * Remote limit switch source. User can choose between a remote
1288 * Talon SRX, CANifier, or deactivate the feature.
1289 * @param normalOpenOrClose
1290 * Setting for normally open, normally closed, or disabled. This
1291 * setting matches the Phoenix Tuner drop down.
1292 * @param deviceID
1293 * Device ID of remote source (Talon SRX or CANifier device ID).
1294 * @param timeoutMs
1295 * Timeout value in ms. If nonzero, function will wait for config
1296 * success and report an error if it times out. If zero, no
1297 * blocking or checking is performed.
1298 * @return Error Code generated by function. 0 indicates no error.
1299 */
1301 RemoteLimitSwitchSource type, LimitSwitchNormal normalOpenOrClose,
1302 int deviceID, int timeoutMs = 0);
1303 /**
1304 * Sets the enable state for limit switches.
1305 *
1306 * @param enable
1307 * Enable state for limit switches.
1308 **/
1310 //------ local limit switch ----------//
1311 /**
1312 * Configures a limit switch for a local/remote source.
1313 *
1314 * For example, a CAN motor controller may need to monitor the Limit-R pin
1315 * of another Talon, CANifier, or local Gadgeteer feedback connector.
1316 *
1317 * If the sensor is remote, a device ID of zero is assumed. If that's not
1318 * desired, use the four parameter version of this function.
1319 *
1320 * @param type
1321 * Limit switch source. User can choose
1322 * between the feedback connector, remote Talon SRX, CANifier, or
1323 * deactivate the feature.
1324 * @param normalOpenOrClose
1325 * Setting for normally open, normally closed, or disabled. This
1326 * setting matches the Phoenix Tuner drop down.
1327 * @param timeoutMs
1328 * Timeout value in ms. If nonzero, function will wait for config
1329 * success and report an error if it times out. If zero, no
1330 * blocking or checking is performed.
1331 * @return Error Code generated by function. 0 indicates no error.
1332 */
1334 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
1335 /**
1336 * Configures a limit switch for a local/remote source.
1337 *
1338 * For example, a CAN motor controller may need to monitor the Limit-R pin
1339 * of another Talon, CANifier, or local Gadgeteer feedback connector.
1340 *
1341 * If the sensor is remote, a device ID of zero is assumed. If that's not
1342 * desired, use the four parameter version of this function.
1343 *
1344 * @param type
1345 * Limit switch source. User can choose
1346 * between the feedback connector, remote Talon SRX, CANifier, or
1347 * deactivate the feature.
1348 * @param normalOpenOrClose
1349 * Setting for normally open, normally closed, or disabled. This
1350 * setting matches the Phoenix Tuner drop down.
1351 * @param timeoutMs
1352 * Timeout value in ms. If nonzero, function will wait for config
1353 * success and report an error if it times out. If zero, no
1354 * blocking or checking is performed.
1355 * @return Error Code generated by function. 0 indicates no error.
1356 */
1358 LimitSwitchNormal normalOpenOrClose, int timeoutMs = 0);
1359 //------ soft limit ----------//
1360 /**
1361 * Configures the forward soft limit threhold.
1362 *
1363 * @param forwardSensorLimit
1364 * Forward Sensor Position Limit (in raw sensor units).
1365 * @param timeoutMs
1366 * Timeout value in ms. If nonzero, function will wait for
1367 * config success and report an error if it times out.
1368 * If zero, no blocking or checking is performed.
1369 * @return Error Code generated by function. 0 indicates no error.
1370 */
1372 int timeoutMs = 0);
1373 /**
1374 * Configures the reverse soft limit threshold.
1375 *
1376 * @param reverseSensorLimit
1377 * Reverse Sensor Position Limit (in raw sensor units).
1378 * @param timeoutMs
1379 * Timeout value in ms. If nonzero, function will wait for
1380 * config success and report an error if it times out.
1381 * If zero, no blocking or checking is performed.
1382 * @return Error Code generated by function. 0 indicates no error.
1383 */
1385 int timeoutMs = 0);
1386 /**
1387 * Configures the forward soft limit enable.
1388 *
1389 * @param enable
1390 * Forward Sensor Position Limit Enable.
1391 * @param timeoutMs
1392 * Timeout value in ms. If nonzero, function will wait for
1393 * config success and report an error if it times out.
1394 * If zero, no blocking or checking is performed.
1395 * @return Error Code generated by function. 0 indicates no error.
1396 */
1398 int timeoutMs = 0);
1399 /**
1400 * Configures the reverse soft limit enable.
1401 *
1402 * @param enable
1403 * Reverse Sensor Position Limit Enable.
1404 * @param timeoutMs
1405 * Timeout value in ms. If nonzero, function will wait for config
1406 * success and report an error if it times out. If zero, no
1407 * blocking or checking is performed.
1408 * @return Error Code generated by function. 0 indicates no error.
1409 */
1411 int timeoutMs = 0);
1412 /**
1413 * Can be used to override-disable the soft limits.
1414 * This function can be used to quickly disable soft limits without
1415 * having to modify the persistent configuration.
1416 *
1417 * @param enable
1418 * Enable state for soft limit switches.
1419 */
1420 virtual void OverrideSoftLimitsEnable(bool enable);
1421 //------ Current Lim ----------//
1422 /* not available in base */
1423 //------ General Close loop ----------//
1424 /**
1425 * Sets the 'P' constant in the given parameter slot.
1426 * This is multiplied by closed loop error in sensor units.
1427 * Note the closed loop output interprets a final value of 1023 as full output.
1428 * So use a gain of '0.25' to get full output if err is 4096u (Mag Encoder 1 rotation)
1429 *
1430 * @param slotIdx
1431 * Parameter slot for the constant.
1432 * @param value
1433 * Value of the P constant.
1434 * @param timeoutMs
1435 * Timeout value in ms. If nonzero, function will wait for
1436 * config success and report an error if it times out.
1437 * If zero, no blocking or checking is performed.
1438 * @return Error Code generated by function. 0 indicates no error.
1439 */
1440 virtual ctre::phoenix::ErrorCode Config_kP(int slotIdx, double value, int timeoutMs = 0);
1441 /**
1442 * Sets the 'I' constant in the given parameter slot.
1443 * This is multiplied by accumulated closed loop error in sensor units every PID Loop.
1444 * Note the closed loop output interprets a final value of 1023 as full output.
1445 * So use a gain of '0.00025' to get full output if err is 4096u for 1000 loops (accumulater holds 4,096,000),
1446 * [which is equivalent to one CTRE mag encoder rotation for 1000 milliseconds].
1447 *
1448 * @param slotIdx
1449 * Parameter slot for the constant.
1450 * @param value
1451 * Value of the I constant.
1452 * @param timeoutMs
1453 * Timeout value in ms. If nonzero, function will wait for
1454 * config success and report an error if it times out.
1455 * If zero, no blocking or checking is performed.
1456 * @return Error Code generated by function. 0 indicates no error.
1457 */
1458 virtual ctre::phoenix::ErrorCode Config_kI(int slotIdx, double value, int timeoutMs = 0);
1459 /**
1460 * Sets the 'D' constant in the given parameter slot.
1461 *
1462 * This is multiplied by derivative error (sensor units per PID loop, typically 1ms).
1463 * Note the closed loop output interprets a final value of 1023 as full output.
1464 * So use a gain of '250' to get full output if derr is 4096u (Mag Encoder 1 rotation) per 1000 loops (typ 1 sec)
1465 *
1466 * @param slotIdx
1467 * Parameter slot for the constant.
1468 * @param value
1469 * Value of the D constant.
1470 * @param timeoutMs
1471 * Timeout value in ms. If nonzero, function will wait for
1472 * config success and report an error if it times out.
1473 * If zero, no blocking or checking is performed.
1474 * @return Error Code generated by function. 0 indicates no error.
1475 */
1476 virtual ctre::phoenix::ErrorCode Config_kD(int slotIdx, double value, int timeoutMs = 0);
1477 /**
1478 * Sets the 'F' constant in the given parameter slot.
1479 *
1480 * See documentation for calculation details.
1481 * If using velocity, motion magic, or motion profile,
1482 * use (1023 * duty-cycle / sensor-velocity-sensor-units-per-100ms).
1483 *
1484 * @param slotIdx
1485 * Parameter slot for the constant.
1486 * @param value
1487 * Value of the F constant.
1488 * @param timeoutMs
1489 * Timeout value in ms. If nonzero, function will wait for
1490 * config success and report an error if it times out.
1491 * If zero, no blocking or checking is performed.
1492 * @return Error Code generated by function. 0 indicates no error.
1493 */
1494 virtual ctre::phoenix::ErrorCode Config_kF(int slotIdx, double value, int timeoutMs = 0);
1495 /**
1496 * Sets the Integral Zone constant in the given parameter slot. If the
1497 * (absolute) closed-loop error is outside of this zone, integral
1498 * accumulator is automatically cleared. This ensures than integral wind up
1499 * events will stop after the sensor gets far enough from its target.
1500 *
1501 * @param slotIdx
1502 * Parameter slot for the constant.
1503 * @param izone
1504 * Value of the Integral Zone constant (closed loop error units X
1505 * 1ms).
1506 * @param timeoutMs
1507 * Timeout value in ms. If nonzero, function will wait for config
1508 * success and report an error if it times out. If zero, no
1509 * blocking or checking is performed.
1510 * @return Error Code generated by function. 0 indicates no error.
1511 */
1512 virtual ctre::phoenix::ErrorCode Config_IntegralZone(int slotIdx, double izone,
1513 int timeoutMs = 0);
1514 /**
1515 * Sets the allowable closed-loop error in the given parameter slot.
1516 *
1517 * @param slotIdx
1518 * Parameter slot for the constant.
1519 * @param allowableCloseLoopError
1520 * Value of the allowable closed-loop error in sensor units (or sensor units per 100ms for velocity).
1521 * @param timeoutMs
1522 * Timeout value in ms. If nonzero, function will wait for
1523 * config success and report an error if it times out.
1524 * If zero, no blocking or checking is performed.
1525 * @return Error Code generated by function. 0 indicates no error.
1526 */
1528 double allowableCloseLoopError, int timeoutMs = 0);
1529 /**
1530 * Sets the maximum integral accumulator in the given parameter slot.
1531 *
1532 * @param slotIdx
1533 * Parameter slot for the constant.
1534 * @param iaccum
1535 * Value of the maximum integral accumulator (closed loop error
1536 * units X 1ms).
1537 * @param timeoutMs
1538 * Timeout value in ms. If nonzero, function will wait for config
1539 * success and report an error if it times out. If zero, no
1540 * blocking or checking is performed.
1541 * @return Error Code generated by function. 0 indicates no error.
1542 */
1543 virtual ctre::phoenix::ErrorCode ConfigMaxIntegralAccumulator(int slotIdx, double iaccum,
1544 int timeoutMs = 0);
1545 /**
1546 * Sets the peak closed-loop output. This peak output is slot-specific and
1547 * is applied to the output of the associated PID loop.
1548 * This setting is seperate from the generic Peak Output setting.
1549 *
1550 * @param slotIdx
1551 * Parameter slot for the constant.
1552 * @param percentOut
1553 * Peak Percent Output from 0 to 1. This value is absolute and
1554 * the magnitude will apply in both forward and reverse directions.
1555 * @param timeoutMs
1556 * Timeout value in ms. If nonzero, function will wait for
1557 * config success and report an error if it times out.
1558 * If zero, no blocking or checking is performed.
1559 * @return Error Code generated by function. 0 indicates no error.
1560 */
1561 virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeakOutput(int slotIdx, double percentOut, int timeoutMs = 0);
1562 /**
1563 * Sets the loop time (in milliseconds) of the PID closed-loop calculations.
1564 * Default value is 1 ms.
1565 *
1566 * @param slotIdx
1567 * Parameter slot for the constant.
1568 * @param loopTimeMs
1569 * Loop timing of the closed-loop calculations. Minimum value of
1570 * 1 ms, maximum of 64 ms.
1571 * @param timeoutMs
1572 * Timeout value in ms. If nonzero, function will wait for
1573 * config success and report an error if it times out.
1574 * If zero, no blocking or checking is performed.
1575 * @return Error Code generated by function. 0 indicates no error.
1576 */
1577 virtual ctre::phoenix::ErrorCode ConfigClosedLoopPeriod(int slotIdx, int loopTimeMs, int timeoutMs = 0);
1578
1579 /**
1580 * Configures the Polarity of the Auxiliary PID (PID1).
1581 *
1582 * Standard Polarity:
1583 * Primary Output = PID0 + PID1,
1584 * Auxiliary Output = PID0 - PID1,
1585 *
1586 * Inverted Polarity:
1587 * Primary Output = PID0 - PID1,
1588 * Auxiliary Output = PID0 + PID1,
1589 *
1590 * @param invert
1591 * If true, use inverted PID1 output polarity.
1592 * @param timeoutMs
1593 * Timeout value in ms. If nonzero, function will wait for config
1594 * success and report an error if it times out. If zero, no
1595 * blocking or checking is performed.
1596 * @return Error Code
1597 */
1598 virtual ctre::phoenix::ErrorCode ConfigAuxPIDPolarity(bool invert, int timeoutMs = 0);
1599
1600 /**
1601 * Configures all slot persistant settings
1602 *
1603 * @param slot Object with all of the slot persistant settings
1604 * @param slotIdx Index of slot to configure
1605 * @param timeoutMs
1606 * Timeout value in ms. If nonzero, function will wait for
1607 * config success and report an error if it times out.
1608 * If zero, no blocking or checking is performed.
1609 *
1610 * @return Error Code generated by function. 0 indicates no error.
1611 */
1612 ctre::phoenix::ErrorCode ConfigureSlot(const SlotConfiguration& slot, int slotIdx, int timeoutMs);
1613
1614 //------ Close loop State ----------//
1615 /**
1616 * Sets the integral accumulator. Typically this is used to clear/zero the
1617 * integral accumulator, however some use cases may require seeding the
1618 * accumulator for a faster response.
1619 *
1620 * @param iaccum
1621 * Value to set for the integral accumulator (closed loop error
1622 * units X 1ms).
1623 * @param pidIdx
1624 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1625 * @param timeoutMs
1626 * Timeout value in ms. If nonzero, function will wait for config
1627 * success and report an error if it times out. If zero, no
1628 * blocking or checking is performed.
1629 * @return Error Code generated by function. 0 indicates no error.
1630 */
1631 virtual ctre::phoenix::ErrorCode SetIntegralAccumulator(double iaccum, int pidIdx = 0, int timeoutMs = 0);
1632 /**
1633 * Gets the closed-loop error. The units depend on which control mode is in
1634 * use.
1635 *
1636 * If closed-loop is seeking a target sensor position, closed-loop error is the difference between target
1637 * and current sensor value (in sensor units. Example 4096 units per rotation for CTRE Mag Encoder).
1638 *
1639 * If closed-loop is seeking a target sensor velocity, closed-loop error is the difference between target
1640 * and current sensor value (in sensor units per 100ms).
1641 *
1642 * If using motion profiling or Motion Magic, closed loop error is calculated against the current target,
1643 * and not the "final" target at the end of the profile/movement.
1644 *
1645 * See Phoenix-Documentation information on units.
1646 *
1647 * @param pidIdx
1648 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1649 * @return Closed-loop error value.
1650 */
1651 virtual double GetClosedLoopError(int pidIdx = 0);
1652 /**
1653 * Gets the iaccum value.
1654 *
1655 * @param pidIdx
1656 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1657 * @return Integral accumulator value (Closed-loop error X 1ms).
1658 */
1659 virtual double GetIntegralAccumulator(int pidIdx = 0);
1660 /**
1661 * Gets the derivative of the closed-loop error.
1662 *
1663 * @param pidIdx
1664 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1665 * @return The error derivative value.
1666 */
1667 virtual double GetErrorDerivative(int pidIdx = 0);
1668
1669 /**
1670 * Selects which profile slot to use for closed-loop control.
1671 *
1672 * @param slotIdx
1673 * Profile slot to select.
1674 * @param pidIdx
1675 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1676 **/
1677 virtual ctre::phoenix::ErrorCode SelectProfileSlot(int slotIdx, int pidIdx);
1678
1679 /**
1680 * Gets the current target of a given closed loop.
1681 *
1682 * @param pidIdx
1683 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1684 * @return The closed loop target.
1685 */
1686 virtual double GetClosedLoopTarget(int pidIdx = 0);
1687 /**
1688 * Gets the active trajectory target position using
1689 * MotionMagic/MotionProfile control modes.
1690 *
1691 * @return The Active Trajectory Position in sensor units.
1692 */ virtual double GetActiveTrajectoryPosition(int pidIdx = 0);
1693 /**
1694 * Gets the active trajectory target velocity using
1695 * MotionMagic/MotionProfile control modes.
1696 *
1697 * @return The Active Trajectory Velocity in sensor units per 100ms.
1698 */
1699 virtual double GetActiveTrajectoryVelocity(int pidIdx = 0); /**
1700 * Gets the active trajectory arbitrary feedforward using
1701 * MotionMagic/MotionProfile control modes.
1702 *
1703 * @param pidIdx
1704 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
1705 * @return The Active Trajectory ArbFeedFwd in units of percent output
1706 * (where 0.01 is 1%).
1707 */
1708 virtual double GetActiveTrajectoryArbFeedFwd(int pidIdx = 0);
1709
1710 //------ Motion Profile Settings used in Motion Magic ----------//
1711 /**
1712 * Sets the Motion Magic Cruise Velocity. This is the peak target velocity
1713 * that the motion magic curve generator can use.
1714 *
1715 * @param sensorUnitsPer100ms
1716 * Motion Magic Cruise Velocity (in raw sensor units per 100 ms).
1717 * @param timeoutMs
1718 * Timeout value in ms. If nonzero, function will wait for config
1719 * success and report an error if it times out. If zero, no
1720 * blocking or checking is performed.
1721 * @return Error Code generated by function. 0 indicates no error.
1722 */
1723 virtual ctre::phoenix::ErrorCode ConfigMotionCruiseVelocity(double sensorUnitsPer100ms,
1724 int timeoutMs = 0);
1725 /**
1726 * Sets the Motion Magic Acceleration. This is the target acceleration that
1727 * the motion magic curve generator can use.
1728 *
1729 * @param sensorUnitsPer100msPerSec
1730 * Motion Magic Acceleration (in raw sensor units per 100 ms per
1731 * second).
1732 * @param timeoutMs
1733 * Timeout value in ms. If nonzero, function will wait for config
1734 * success and report an error if it times out. If zero, no
1735 * blocking or checking is performed.
1736 * @return Error Code generated by function. 0 indicates no error.
1737 */
1738 virtual ctre::phoenix::ErrorCode ConfigMotionAcceleration(double sensorUnitsPer100msPerSec,
1739 int timeoutMs = 0);
1740 /**
1741 * Sets the Motion Magic S Curve Strength.
1742 * Call this before using Motion Magic.
1743 * Modifying this during a Motion Magic action should be avoided.
1744 *
1745 * @param curveStrength
1746 * 0 to use Trapezoidal Motion Profile. [1,8] for S-Curve (greater value yields greater smoothing).
1747 * @param timeoutMs
1748 * Timeout value in ms. If nonzero, function will wait for config
1749 * success and report an error if it times out. If zero, no
1750 * blocking or checking is performed.
1751 * @return Error Code generated by function. 0 indicates no error.
1752 */
1753 virtual ctre::phoenix::ErrorCode ConfigMotionSCurveStrength(int curveStrength, int timeoutMs = 0);
1754 //------ Motion Profile Buffer ----------//
1755 /**
1756 * Clear the buffered motion profile in both controller's RAM (bottom), and in the
1757 * API (top).
1758 */
1760 /**
1761 * Retrieve just the buffer count for the api-level (top) buffer. This
1762 * routine performs no CAN or data structure lookups, so its fast and ideal
1763 * if caller needs to quickly poll the progress of trajectory points being
1764 * emptied into controller's RAM. Otherwise just use GetMotionProfileStatus.
1765 *
1766 * @return number of trajectory points in the top buffer.
1767 */
1769 /**
1770 * Push another trajectory point into the top level buffer (which is emptied
1771 * into the motor controller's bottom buffer as room allows).
1772 * @param trajPt to push into buffer.
1773 * The members should be filled in with these values...
1774 *
1775 * targPos: servo position in sensor units.
1776 * targVel: velocity to feed-forward in sensor units
1777 * per 100ms.
1778 * profileSlotSelect0 Which slot to get PIDF gains. PID is used for position servo. F is used
1779 * as the Kv constant for velocity feed-forward. Typically this is hardcoded
1780 * to the a particular slot, but you are free gain schedule if need be.
1781 * Choose from [0,3]
1782 * profileSlotSelect1 Which slot to get PIDF gains for auxiliary PId.
1783 * This only has impact during MotionProfileArc Control mode.
1784 * Choose from [0,1].
1785 * isLastPoint set to nonzero to signal motor controller to keep processing this
1786 * trajectory point, instead of jumping to the next one
1787 * when timeDurMs expires. Otherwise MP executer will
1788 * eventually see an empty buffer after the last point
1789 * expires, causing it to assert the IsUnderRun flag.
1790 * However this may be desired if calling application
1791 * never wants to terminate the MP.
1792 * zeroPos set to nonzero to signal motor controller to "zero" the selected
1793 * position sensor before executing this trajectory point.
1794 * Typically the first point should have this set only thus
1795 * allowing the remainder of the MP positions to be relative to
1796 * zero.
1797 * timeDur Duration to apply this trajectory pt.
1798 * This time unit is ADDED to the exising base time set by
1799 * configMotionProfileTrajectoryPeriod().
1800 * @return CTR_OKAY if trajectory point push ok. ErrorCode if buffer is
1801 * full due to kMotionProfileTopBufferCapacity.
1802 */
1804 /**
1805 * @brief Simple one-shot firing of a complete MP.
1806 * Starting in 2019, MPs can be fired by building a Buffered Trajectory Point Stream, and calling this routine.
1807 *
1808 * Once called, the motor controller software will automatically ...
1809 * [1] Clear the firmware buffer of trajectory points.
1810 * [2] Clear the underrun flags
1811 * [3] Reset an index within the Buffered Trajectory Point Stream (so that the same profile can be run again and again).
1812 * [4] Start a background thread to manage MP streaming (if not already running).
1813 * [5a] If current control mode already matches motionProfControlMode, set MPE Output to "Hold".
1814 * [5b] If current control mode does not matches motionProfControlMode, apply motionProfControlMode and set MPE Output to "Disable".
1815 * [6] Stream the trajectory points into the device's firmware buffer.
1816 * [7] Once motor controller has at least minBufferedPts worth in the firmware buffer, MP will automatically start (MPE Output set to "Enable").
1817 * [8] Wait until MP finishes, then transitions the Motion Profile Executor's output to "Hold".
1818 * [9] IsMotionProfileFinished() will now return true.
1819 *
1820 * Calling application can use IsMotionProfileFinished() to determine when internal state machine reaches [7].
1821 * Calling application can cancel MP by calling set(). Otherwise do not call set() until MP has completed.
1822 *
1823 * The legacy API from previous years requires the calling application to pass points via the ProcessMotionProfileBuffer and PushMotionProfileTrajectory.
1824 * This is no longer required if using this StartMotionProfile/IsMotionProfileFinished API.
1825 *
1826 * @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.
1827 * @param minBufferedPts Minimum number of firmware buffered points before starting MP.
1828 * Do not exceed device's firmware buffer capacity or MP will never fire (120 for Motion Profile, or 60 for Motion Profile Arc).
1829 * Recommendation value for this would be five to ten samples depending on timeDur of the trajectory point.
1830 * @param motionProfControlMode Pass MotionProfile or MotionProfileArc.
1831 * @return nonzero error code if operation fails.
1832 */
1834 /**
1835 * @brief Determine if running MP is complete.
1836 * This requires using the StartMotionProfile routine to start the MP.
1837 * That is because managing the trajectory points is now done in a background thread (if StartMotionProfile is called).
1838 *
1839 * If calling application uses the legacy API (more-complex buffering API) from previous years, than this API will
1840 * not return true.
1841 *
1842 * @return true if MP was started using StartMotionProfile, and it has completed execution (MPE is now in "hold").
1843 */
1845 /**
1846 * Retrieve just the buffer full for the api-level (top) buffer. This
1847 * routine performs no CAN or data structure lookups, so its fast and ideal
1848 * if caller needs to quickly poll. Otherwise just use
1849 * GetMotionProfileStatus.
1850 *
1851 * @return number of trajectory points in the top buffer.
1852 */
1854 /**
1855 * This must be called periodically to funnel the trajectory points from the
1856 * API's top level buffer to the controller's bottom level buffer. Recommendation
1857 * is to call this twice as fast as the execution rate of the motion
1858 * profile. So if MP is running with 20ms trajectory points, try calling
1859 * this routine every 10ms. All motion profile functions are thread-safe
1860 * through the use of a mutex, so there is no harm in having the caller
1861 * utilize threading.
1862 */
1864 /**
1865 * Retrieve all status information.
1866 * For best performance, Caller can snapshot all status information regarding the
1867 * motion profile executer.
1868 *
1869 * @param statusToFill Caller supplied object to fill.
1870 *
1871 * The members are filled, as follows...
1872 *
1873 * topBufferRem: The available empty slots in the trajectory buffer.
1874 * The robot API holds a "top buffer" of trajectory points, so your applicaion
1875 * can dump several points at once. The API will then stream them into the
1876 * low-level buffer, allowing the motor controller to act on them.
1877 *
1878 * topBufferRem: The number of points in the top trajectory buffer.
1879 *
1880 * btmBufferCnt: The number of points in the low level controller buffer.
1881 *
1882 * hasUnderrun: Set if isUnderrun ever gets set.
1883 * Can be manually cleared by ClearMotionProfileHasUnderrun() or automatically cleared by StartMotionProfile().
1884 *
1885 * isUnderrun: This is set if controller needs to shift a point from its buffer into
1886 * the active trajectory point however
1887 * the buffer is empty.
1888 * This gets cleared automatically when is resolved.
1889 *
1890 * activePointValid: True if the active trajectory point is not empty, false otherwise. The members in activePoint are only valid if this signal is set.
1891 *
1892 * isLast: is set/cleared based on the MP executer's current
1893 * trajectory point's IsLast value. This assumes
1894 * IsLast was set when PushMotionProfileTrajectory
1895 * was used to insert the currently processed trajectory
1896 * point.
1897 *
1898 * profileSlotSelect: The currently processed trajectory point's
1899 * selected slot. This can differ in the currently selected slot used
1900 * for Position and Velocity servo modes
1901 *
1902 * outputEnable: The current output mode of the motion profile
1903 * executer (disabled, enabled, or hold). When changing the set()
1904 * value in MP mode, it's important to check this signal to
1905 * confirm the change takes effect before interacting with the top buffer.
1906 */
1908 /**
1909 * Clear the "Has Underrun" flag. Typically this is called after application
1910 * has confirmed an underrun had occured.
1911 *
1912 * @param timeoutMs
1913 * Timeout value in ms. If nonzero, function will wait for config
1914 * success and report an error if it times out. If zero, no
1915 * blocking or checking is performed.
1916 * @return Error Code generated by function. 0 indicates no error.
1917 */
1919 /**
1920 * Calling application can opt to speed up the handshaking between the robot
1921 * API and the controller to increase the download rate of the controller's Motion
1922 * Profile. Ideally the period should be no more than half the period of a
1923 * trajectory point.
1924 *
1925 * @param periodMs
1926 * The transmit period in ms.
1927 * @return Error Code generated by function. 0 indicates no error.
1928 */
1930 /**
1931 * When trajectory points are processed in the motion profile executer, the MPE determines
1932 * how long to apply the active trajectory point by summing baseTrajDurationMs with the
1933 * timeDur of the trajectory point (see TrajectoryPoint).
1934 *
1935 * This allows general selection of the execution rate of the points with 1ms resolution,
1936 * while allowing some degree of change from point to point.
1937 * @param baseTrajDurationMs The base duration time of every trajectory point.
1938 * This is summed with the trajectory points unique timeDur.
1939 * @param timeoutMs
1940 * Timeout value in ms. If nonzero, function will wait for
1941 * config success and report an error if it times out.
1942 * If zero, no blocking or checking is performed.
1943 * @return Error Code generated by function. 0 indicates no error.
1944 */
1945 virtual ctre::phoenix::ErrorCode ConfigMotionProfileTrajectoryPeriod(int baseTrajDurationMs, int timeoutMs = 0);
1946 /**
1947 * When trajectory points are processed in the buffer, the motor controller can
1948 * linearly interpolate additional trajectory points between the buffered
1949 * points. The time delta between these interpolated points is 1 ms.
1950 *
1951 * By default this feature is enabled.
1952 *
1953 * @param enable Whether to enable the trajectory point interpolation feature.
1954 * @param timeoutMs
1955 * Timeout value in ms. If nonzero, function will wait for
1956 * config success and report an error if it times out.
1957 * If zero, no blocking or checking is performed.
1958 * @return Error Code generated by function. 0 indicates no error.
1959 */
1961
1962
1963 //------Feedback Device Interaction Settings---------//
1964 /**
1965 * Disables continuous tracking of the position for analog and pulse-width.
1966 * If the signal goes from 4095 to 0 (pulse-width) a motor controller will continue to read 4096 by default.
1967 * If overflow tracking is disabled, it will wrap to 0 (not continuous)
1968 *
1969 * If using pulse-width on CTRE Mag Encoder (within one rotation) or absolute analog sensor (within one rotation),
1970 * setting feedbackNotContinuous to true is recommended, to prevent intermittent
1971 * connections from causing sensor "jumps" of 4096 (or 1024 for analog) units.
1972 *
1973 * @param feedbackNotContinuous True to disable the overflow tracking.
1974 *
1975 * @param timeoutMs
1976 * Timeout value in ms. If nonzero, function will wait for
1977 * config success and report an error if it times out.
1978 * If zero, no blocking or checking is performed.
1979 * @return Error Code generated by function. 0 indicates no error.
1980 */
1981 virtual ErrorCode ConfigFeedbackNotContinuous(bool feedbackNotContinuous, int timeoutMs = 0);
1982 /**
1983 * Disables going to neutral (brake/coast) when a remote sensor is no longer detected.
1984 *
1985 * @param remoteSensorClosedLoopDisableNeutralOnLOS disable going to neutral
1986 *
1987 * @param timeoutMs
1988 * Timeout value in ms. If nonzero, function will wait for
1989 * config success and report an error if it times out.
1990 * If zero, no blocking or checking is performed.
1991 * @return Error Code generated by function. 0 indicates no error.
1992 */
1993 virtual ErrorCode ConfigRemoteSensorClosedLoopDisableNeutralOnLOS(bool remoteSensorClosedLoopDisableNeutralOnLOS, int timeoutMs = 0);
1994 /**
1995 * Enables clearing the position of the feedback sensor when the forward
1996 * limit switch is triggered
1997 *
1998 * @param clearPositionOnLimitF Whether clearing is enabled, defaults false
1999 * @param timeoutMs
2000 * Timeout value in ms. If nonzero, function will wait for
2001 * config success and report an error if it times out.
2002 * If zero, no blocking or checking is performed.
2003 * @return Error Code generated by function. 0 indicates no error.
2004 */
2005 virtual ErrorCode ConfigClearPositionOnLimitF(bool clearPositionOnLimitF, int timeoutMs = 0);
2006 /**
2007 * Enables clearing the position of the feedback sensor when the reverse
2008 * limit switch is triggered
2009 *
2010 * @param clearPositionOnLimitR Whether clearing is enabled, defaults false
2011 * @param timeoutMs
2012 * Timeout value in ms. If nonzero, function will wait for
2013 * config success and report an error if it times out.
2014 * If zero, no blocking or checking is performed.
2015 * @return Error Code generated by function. 0 indicates no error.
2016 */
2017 virtual ErrorCode ConfigClearPositionOnLimitR(bool clearPositionOnLimitR, int timeoutMs = 0);
2018 /**
2019 * Enables clearing the position of the feedback sensor when the quadrature index signal
2020 * is detected
2021 *
2022 * @param clearPositionOnQuadIdx Whether clearing is enabled, defaults false
2023 * @param timeoutMs
2024 * Timeout value in ms. If nonzero, function will wait for
2025 * config success and report an error if it times out.
2026 * If zero, no blocking or checking is performed.
2027 * @return Error Code generated by function. 0 indicates no error.
2028 */
2029 virtual ErrorCode ConfigClearPositionOnQuadIdx(bool clearPositionOnQuadIdx, int timeoutMs = 0);
2030 /**
2031 * Disables limit switches triggering (if enabled) when the sensor is no longer detected.
2032 *
2033 * @param limitSwitchDisableNeutralOnLOS disable triggering
2034 *
2035 * @param timeoutMs
2036 * Timeout value in ms. If nonzero, function will wait for
2037 * config success and report an error if it times out.
2038 * If zero, no blocking or checking is performed.
2039 * @return Error Code generated by function. 0 indicates no error.
2040 */
2041 virtual ErrorCode ConfigLimitSwitchDisableNeutralOnLOS(bool limitSwitchDisableNeutralOnLOS, int timeoutMs = 0);
2042 /**
2043 * Disables soft limits triggering (if enabled) when the sensor is no longer detected.
2044 *
2045 * @param softLimitDisableNeutralOnLOS disable triggering
2046 *
2047 * @param timeoutMs
2048 * Timeout value in ms. If nonzero, function will wait for
2049 * config success and report an error if it times out.
2050 * If zero, no blocking or checking is performed.
2051 * @return Error Code generated by function. 0 indicates no error.
2052 */
2053 virtual ErrorCode ConfigSoftLimitDisableNeutralOnLOS(bool softLimitDisableNeutralOnLOS, int timeoutMs = 0);
2054 /**
2055 * Sets the edges per rotation of a pulse width sensor. (This should be set for
2056 * tachometer use).
2057 *
2058 * @param pulseWidthPeriod_EdgesPerRot edges per rotation
2059 *
2060 * @param timeoutMs
2061 * Timeout value in ms. If nonzero, function will wait for
2062 * config success and report an error if it times out.
2063 * If zero, no blocking or checking is performed.
2064 * @return Error Code generated by function. 0 indicates no error.
2065 */
2066 virtual ErrorCode ConfigPulseWidthPeriod_EdgesPerRot(int pulseWidthPeriod_EdgesPerRot, int timeoutMs = 0);
2067 /**
2068 * Sets the number of samples to use in smoothing a pulse width sensor with a rolling
2069 * average. Default is 1 (no smoothing).
2070 *
2071 * @param pulseWidthPeriod_FilterWindowSz samples for rolling avg
2072 *
2073 * @param timeoutMs
2074 * Timeout value in ms. If nonzero, function will wait for
2075 * config success and report an error if it times out.
2076 * If zero, no blocking or checking is performed.
2077 * @return Error Code generated by function. 0 indicates no error.
2078 */
2079 virtual ErrorCode ConfigPulseWidthPeriod_FilterWindowSz(int pulseWidthPeriod_FilterWindowSz, int timeoutMs = 0);
2080
2081 //------ error ----------//
2082 /**
2083 * Gets the last error generated by this object. Not all functions return an
2084 * error code but can potentially report errors. This function can be used
2085 * to retrieve those error codes.
2086 *
2087 * @return Last Error Code generated by a function.
2088 */
2090 //------ Faults ----------//
2091 /**
2092 * Polls the various fault flags.
2093 *
2094 * @param toFill
2095 * Caller's object to fill with latest fault flags.
2096 * @return Last Error Code generated by a function.
2097 */
2099 /**
2100 * Polls the various sticky fault flags.
2101 *
2102 * @param toFill
2103 * Caller's object to fill with latest sticky fault flags.
2104 * @return Last Error Code generated by a function.
2105 */
2107 /**
2108 * Clears all sticky faults.
2109 *
2110 * @param timeoutMs
2111 * Timeout value in ms. If nonzero, function will wait for config
2112 * success and report an error if it times out. If zero, no
2113 * blocking or checking is performed.
2114 * @return Last Error Code generated by a function.
2115 */
2117 //------ Firmware ----------//
2118 /**
2119 * Gets the firmware version of the device.
2120 *
2121 * @return Firmware version of device. For example: version 1-dot-2 is
2122 * 0x0102.
2123 */
2124 virtual int GetFirmwareVersion();
2125 /**
2126 * Returns true if the device has reset since last call.
2127 *
2128 * @return Has a Device Reset Occurred?
2129 */
2130 virtual bool HasResetOccurred();
2131 //------ Custom Persistent Params ----------//
2132 /**
2133 * Sets the value of a custom parameter. This is for arbitrary use.
2134 *
2135 * Sometimes it is necessary to save calibration/limit/target information in
2136 * the device. Particularly if the device is part of a subsystem that can be
2137 * replaced.
2138 *
2139 * @param newValue
2140 * Value for custom parameter.
2141 * @param paramIndex
2142 * Index of custom parameter [0,1]
2143 * @param timeoutMs
2144 * Timeout value in ms. If nonzero, function will wait for config
2145 * success and report an error if it times out. If zero, no
2146 * blocking or checking is performed.
2147 * @return Error Code generated by function. 0 indicates no error.
2148 */
2149 virtual ctre::phoenix::ErrorCode ConfigSetCustomParam(int newValue, int paramIndex,
2150 int timeoutMs = 0);
2151 /**
2152 * Gets the value of a custom parameter.
2153 *
2154 * @param paramIndex
2155 * Index of custom parameter [0,1].
2156 * @param timeoutMs
2157 * Timeout value in ms. If nonzero, function will wait for config
2158 * success and report an error if it times out. If zero, no
2159 * blocking or checking is performed.
2160 * @return Value of the custom param.
2161 */
2162 virtual int ConfigGetCustomParam(int paramIndex,
2163 int timeoutMs = 0);
2164 //------ Generic Param API, typically not used ----------//
2165 /**
2166 * Sets a parameter. Generally this is not used. This can be utilized in -
2167 * Using new features without updating API installation. - Errata
2168 * workarounds to circumvent API implementation. - Allows for rapid testing
2169 * / unit testing of firmware.
2170 *
2171 * @param param
2172 * Parameter enumeration.
2173 * @param value
2174 * Value of parameter.
2175 * @param subValue
2176 * Subvalue for parameter. Maximum value of 255.
2177 * @param ordinal
2178 * Ordinal of parameter.
2179 * @param timeoutMs
2180 * Timeout value in ms. If nonzero, function will wait for config
2181 * success and report an error if it times out. If zero, no
2182 * blocking or checking is performed.
2183 * @return Error Code generated by function. 0 indicates no error.
2184 */
2186 uint8_t subValue, int ordinal, int timeoutMs = 0);
2187 /**
2188 * Gets a parameter.
2189 *
2190 * @param param
2191 * Parameter enumeration.
2192 * @param ordinal
2193 * Ordinal of parameter.
2194 * @param timeoutMs
2195 * Timeout value in ms. If nonzero, function will wait for
2196 * config success and report an error if it times out.
2197 * If zero, no blocking or checking is performed.
2198 * @return Value of parameter.
2199 */
2200 virtual double ConfigGetParameter(ctre::phoenix::ParamEnum param, int ordinal, int timeoutMs = 0);
2201 /**
2202 * Gets a parameter by passing an int by reference
2203 *
2204 * @param param
2205 * Parameter enumeration
2206 * @param valueToSend
2207 * Value to send to parameter
2208 * @param valueReceived
2209 * Reference to integer to receive
2210 * @param subValue
2211 * SubValue of parameter
2212 * @param ordinal
2213 * Ordinal of parameter
2214 * @param timeoutMs
2215 * Timeout value in ms. If nonzero, function will wait for
2216 * config success and report an error if it times out.
2217 * If zero, no blocking or checking is performed.
2218 * @return Error Code generated by function. 0 indicates no error.
2219 */
2220 virtual ErrorCode ConfigGetParameter(ParamEnum param, int32_t valueToSend,
2221 int32_t& valueReceived, uint8_t& subValue, int32_t ordinal,
2222 int32_t timeoutMs);
2223 //------ Misc. ----------//
2224 virtual int GetBaseID();
2225 /**
2226 * @return control mode motor controller is in
2227 */
2229 // ----- Follower ------//
2230 /**
2231 * Set the control mode and output value so that this motor controller will
2232 * follow another motor controller. Currently supports following Victor SPX,
2233 * Talon SRX, and Talon FX.
2234 *
2235 * @param masterToFollow
2236 * Motor Controller object to follow.
2237 * @param followerType
2238 * Type of following control. Use AuxOutput1 to follow the master
2239 * device's auxiliary output 1.
2240 * Use PercentOutput for standard follower mode.
2241 */
2243 /**
2244 * Set the control mode and output value so that this motor controller will
2245 * follow another motor controller. Currently supports following Victor SPX,
2246 * Talon SRX, and Talon FX.
2247 */
2248 virtual void Follow(IMotorController& masterToFollow);
2249 /**
2250 * When master makes a device, this routine is called to signal the update.
2251 */
2252 virtual void ValueUpdated();
2253
2254
2255 //-------Config All----------//
2256 /**
2257 * Gets all slot persistant settings.
2258 *
2259 * @param slot Object with all of the slot persistant settings
2260 * @param slotIdx Parameter slot for the constant.
2261 * @param timeoutMs
2262 * Timeout value in ms. If nonzero, function will wait for
2263 * config success and report an error if it times out.
2264 * If zero, no blocking or checking is performed.
2265 */
2266 void GetSlotConfigs(SlotConfiguration& slot, int slotIdx = 0, int timeoutMs = 50);
2267 /**
2268 * Gets all filter persistant settings.
2269 *
2270 * @param Filter Object with all of the filter persistant settings
2271 * @param ordinal 0 for remote sensor 0 and 1 for remote sensor 1.
2272 * @param timeoutMs
2273 * Timeout value in ms. If nonzero, function will wait for
2274 * config success and report an error if it times out.
2275 * If zero, no blocking or checking is performed.
2276 */
2277 void GetFilterConfigs(FilterConfiguration& Filter, int ordinal = 0, int timeoutMs = 50);
2278
2279 /**
2280 * @return CCI handle for child classes.
2281 */
2282 void* GetHandle();
2283
2284 };// class BaseMotorController
2285 } // namespace can
2286 } // namespace motorcontrol
2287 } // namespace phoenix
2288} // 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:94
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:260
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:131
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
WPI Compliant CANcoder class.
Definition CANCoderStatusFrame.h:4
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