CTRE Phoenix C++ 5.33.1
TalonFX.h
Go to the documentation of this file.
1/* Copyright (C) Cross The Road Electronics 2024 */
2#pragma once
3#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
4#pragma warning (push)
5#pragma warning (disable : 4250)
6#endif
7
15
16namespace ctre {
17 namespace phoenix {
18 namespace motorcontrol {
19 namespace can {
20
21 /**
22 * Configurables available to TalonFX's PID
23 *
24 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
25 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
26 * Phoenix 6 API. A migration guide is available at
27 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
28 *
29 * If the Phoenix 5 API must be used for this device, the device must have 22.X
30 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
31 * the firmware year dropdown.
32 */
33 struct [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
34 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
35 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
37
38 /**
39 * Configurables available to TalonFX
40 *
41 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
42 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
43 * Phoenix 6 API. A migration guide is available at
44 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
45 *
46 * If the Phoenix 5 API must be used for this device, the device must have 22.X
47 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
48 * the firmware year dropdown.
49 */
51
52 /**
53 * Supply-side current limiting. This is typically used to prevent breakers from tripping.
54 */
56 /**
57 * Stator-side current limiting. This is typically used to limit acceleration/torque and heat generation.
58 */
60
61 /**
62 * Choose the type of motor commutation.
63 */
65
66 /**
67 * Desired Sign / Range for the absolute position register.
68 * Choose unsigned for an absolute range of[0, +1) rotations, [0, 360) deg, etc.
69 * Choose signed for an absolute range of[-0.5, +0.5) rotations, [-180, +180) deg, etc.
70 */
72 /**
73 * Adjusts the zero point for the absolute position register.
74 * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180)
75 * and a hard-limited mechanism may have such a discontinuity in its functional range.
76 * In which case use this config to move the discontinuity outside of the function range.
77 */
79 /**
80 * The sensor initialization strategy to use.This will impact the behavior the next time device boots up.
81 *
82 * Pick the strategy on how to initialize the "Position" register. Depending on the mechanism,
83 * it may be desirable to auto set the Position register to match the Absolute Position(swerve for example).
84 * Or it may be desired to zero the sensor on boot(drivetrain translation sensor or a relative servo).
85 *
86 * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the device is reset.
87 */
89
90 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
91 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
92 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
94 {
95 }
96
97 /**
98 * @return String representation of all the configs
99 */
100 std::string toString() {
101 return toString("");
102 }
103
104 /**
105 * @param prependString
106 * String to prepend to all the configs
107 * @return String representation of all the configs
108 */
109 std::string toString(std::string prependString) {
110
111 std::string retstr;
112 retstr += prependString + ".supplyCurrLimit = " + supplyCurrLimit.ToString() + ";\n";
113 retstr += prependString + ".statorCurrLimit = " + statorCurrLimit.ToString() + ";\n";
114 retstr += prependString + ".motorCommutation = " + std::to_string((int)motorCommutation) + ";\n";
115 retstr += prependString + ".absoluteSensorRange = " + std::to_string(absoluteSensorRange) + ";\n";
116 retstr += prependString + ".integratedSensorOffsetDegrees = " + std::to_string(integratedSensorOffsetDegrees) + ";\n";
117 retstr += prependString + ".initializationStrategy = " + std::to_string(initializationStrategy) + ";\n";
118 retstr += BaseTalonConfiguration::toString(prependString);
119
120 return retstr;
121 }
122 };// struct TalonFXConfiguration
123
124 /**
125 * Util class to help with talon configs
126 *
127 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
128 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
129 * Phoenix 6 API. A migration guide is available at
130 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
131 *
132 * If the Phoenix 5 API must be used for this device, the device must have 22.X
133 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
134 * the firmware year dropdown.
135 */
136 class [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
137 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
138 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
140 private:
141 static struct TalonFXConfiguration _default;
142 public:
143 /**
144 * Determine if specified value is different from default
145 * @param settings settings to compare against
146 * @return if specified value is different from default
147 * @{
148 */
149 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
150 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
151 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
152 static bool SupplyCurrentLimitDifferent(const TalonFXConfiguration& settings) { return (!settings.supplyCurrLimit.Equals(_default.supplyCurrLimit)) || !settings.enableOptimizations; }
153 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
154 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
155 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
156 static bool StatorCurrentDurationDifferent(const TalonFXConfiguration& settings) { return (!settings.statorCurrLimit.Equals(_default.statorCurrLimit)) || !settings.enableOptimizations; }
157 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
158 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
159 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
160 static bool MotorCommutationDifferent(const TalonFXConfiguration& settings) { return (settings.motorCommutation != _default.motorCommutation) || !settings.enableOptimizations; }
161 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
162 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
163 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
164 static bool AbsoluteSensorRangeDifferent(const TalonFXConfiguration& settings) { return (settings.absoluteSensorRange != _default.absoluteSensorRange) || !settings.enableOptimizations; }
165 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
166 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
167 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
169 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
170 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
171 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
172 static bool InitializationStrategyDifferent(const TalonFXConfiguration& settings) { return (settings.initializationStrategy != _default.initializationStrategy) || !settings.enableOptimizations; }
173 /** @} */
174 };
175
176 /**
177 * CTRE Talon FX Motor Controller when used on CAN Bus.
178 *
179 * <pre>
180 * {@code
181 * // Example usage of a TalonFX motor controller
182 * TalonFX motor{0}; // creates a new TalonFX with ID 0
183 *
184 * TalonFXConfiguration config;
185 * config.supplyCurrLimit.enable = true;
186 * config.supplyCurrLimit.triggerThresholdCurrent = 40; // the peak supply current, in amps
187 * config.supplyCurrLimit.triggerThresholdTime = 1.5; // the time at the peak supply current before the limit triggers, in sec
188 * config.supplyCurrLimit.currentLimit = 30; // the current to maintain if the peak supply limit is triggered
189 * motor.ConfigAllSettings(config); // apply the config settings; this selects the quadrature encoder
190 *
191 * motor.Set(TalonFXControlMode::PercentOutput, 0.5); // runs the motor at 50% power
192 *
193 * std::cout << motor.GetSelectedSensorPosition() << std::endl; // prints the position of the selected sensor
194 * std::cout << motor.GetSelectedSensorVelocity() << std::endl; // prints the velocity recorded by the selected sensor
195 * std::cout << motor.GetMotorOutputPercent() << std::endl; // prints the percent output of the motor (0.5)
196 * std::cout << motor.GetStatorCurrent() << std::endl; // prints the output current of the motor
197 *
198 * ErrorCode error = motor.GetLastError(); // gets the last error generated by the motor controller
199 * Faults faults;
200 * ErrorCode faultsError = motor.GetFaults(faults); // fills faults with the current motor controller faults; returns the last error generated
201 *
202 * motor.SetStatusFramePeriod(StatusFrameEnhanced::Status_2_Feedback0, 10); // changes the period of the Status 2 frame (GetSelectedSensor*()) to 10ms
203 * }
204 * </pre>
205 *
206 * @deprecated This device's Phoenix 5 API is deprecated for removal in the
207 * 2025 season. Users should update to Phoenix 6 firmware and migrate to the
208 * Phoenix 6 API. A migration guide is available at
209 * https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html.
210 *
211 * If the Phoenix 5 API must be used for this device, the device must have 22.X
212 * firmware. This firmware is available in Tuner X after selecting Phoenix 5 in
213 * the firmware year dropdown.
214 */
215 class [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
216 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
217 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
218 TalonFX : public virtual BaseTalon
219 {
220 private:
221
222 public:
223 /**
224 * Constructor for a Talon
225 * @param deviceNumber CAN Device ID of TalonFX
226 * @param canbus Name of the CANbus; can be a SocketCAN interface (on Linux),
227 * or a CANivore device name or serial number
228 */
229 TalonFX(int deviceNumber, std::string const &canbus = "");
231 TalonFX() = delete;
232 TalonFX(TalonFX const&) = delete;
233 TalonFX& operator=(TalonFX const&) = delete;
234 // ------ Set output routines. ----------//
235 /**
236 * Sets the appropriate output on the talon, depending on the mode.
237 * @param mode The output mode to apply.
238 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
239 * In Current mode, output value is in amperes.
240 * In Velocity mode, output value is in position change / 100ms.
241 * In Position mode, output value is in encoder ticks or an analog value,
242 * depending on the sensor.
243 * In Follower mode, the output value is the integer device ID of the talon to
244 * duplicate.
245 *
246 * @param value The setpoint value, as described above.
247 *
248 *
249 * Standard Driving Example:
250 * _talonLeft.set(ControlMode.PercentOutput, leftJoy);
251 * _talonRght.set(ControlMode.PercentOutput, rghtJoy);
252 */
253 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
254 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
255 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
256 void Set(TalonFXControlMode mode, double value);
257 /**
258 * @param mode Sets the appropriate output on the talon, depending on the mode.
259 * @param demand0 The output value to apply.
260 * such as advanced feed forward and/or auxiliary close-looping in firmware.
261 * In PercentOutput, the output is between -1.0 and 1.0, with 0.0 as stopped.
262 * In Current mode, output value is in amperes.
263 * In Velocity mode, output value is in position change / 100ms.
264 * In Position mode, output value is in encoder ticks or an analog value,
265 * depending on the sensor. See
266 * In Follower mode, the output value is the integer device ID of the talon to
267 * duplicate.
268 *
269 * @param demand1Type The demand type for demand1.
270 * Neutral: Ignore demand1 and apply no change to the demand0 output.
271 * AuxPID: Use demand1 to set the target for the auxiliary PID 1. Auxiliary
272 * PID is always executed as standard Position PID control.
273 * ArbitraryFeedForward: Use demand1 as an arbitrary additive value to the
274 * demand0 output. In PercentOutput the demand0 output is the motor output,
275 * and in closed-loop modes the demand0 output is the output of PID0.
276 * @param demand1 Supplmental output value.
277 * AuxPID: Target position in Sensor Units
278 * ArbitraryFeedForward: Percent Output between -1.0 and 1.0
279 *
280 *
281 * Arcade Drive Example:
282 * _talonLeft.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, +joyTurn);
283 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.ArbitraryFeedForward, -joyTurn);
284 *
285 * Drive Straight Example:
286 * Note: Selected Sensor Configuration is necessary for both PID0 and PID1.
287 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
288 * _talonRght.set(ControlMode.PercentOutput, joyForward, DemandType.AuxPID, desiredRobotHeading);
289 *
290 * Drive Straight to a Distance Example:
291 * Note: Other configurations (sensor selection, PID gains, etc.) need to be set.
292 * _talonLeft.follow(_talonRght, FollwerType.AuxOutput1);
293 * _talonRght.set(ControlMode.MotionMagic, targetDistance, DemandType.AuxPID, desiredRobotHeading);
294 */
295 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
296 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
297 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
298 void Set(TalonFXControlMode mode, double demand0, DemandType demand1Type, double demand1);
299 //------ Invert behavior ----------//
300 /**
301 * Inverts the hbridge output of the motor controller in relation to the master if present
302 *
303 * This does not impact sensor phase and should not be used to correct sensor polarity.
304 *
305 * This will allow you to either:
306 * - Not invert the motor
307 * - Invert the motor
308 * - Always follow the master regardless of master's inversion
309 * - Always oppose the master regardless of master's inversion
310 *
311 * @param invertType
312 * Invert state to set.
313 */
314 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
315 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
316 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
318 //------ sensor selection ----------//
319 /**
320 * Select the feedback device for the motor controller.
321 *
322 * @param feedbackDevice
323 * Talon FX Feedback Device to select.
324 * @param pidIdx
325 * 0 for Primary closed-loop. 1 for auxiliary closed-loop.
326 * @param timeoutMs
327 * Timeout value in ms. If nonzero, function will wait for
328 * config success and report an error if it times out.
329 * If zero, no blocking or checking is performed.
330 * @return Error Code generated by function. 0 indicates no error.
331 */
332 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
333 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
334 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
335 ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(TalonFXFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
336 //------ Current Limit ----------//
337 /**
338 * Configures the supply-side current limit.
339 * @param currLimitCfg Current limit configuration
340 * @param timeoutMs
341 * Timeout value in ms. If nonzero, function will wait for
342 * config success and report an error if it times out.
343 * If zero, no blocking or checking is performed.
344 * @return Error Code generated by function. 0 indicates no error.
345 */
346 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
347 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
348 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
350 /**
351 * Configures the stator (output) current limit.
352 * @param currLimitCfg Current limit configuration
353 * @param timeoutMs
354 * Timeout value in ms. If nonzero, function will wait for
355 * config success and report an error if it times out.
356 * If zero, no blocking or checking is performed.
357 * @return Error Code generated by function. 0 indicates no error.
358 */
359 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
360 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
361 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
363 /**
364 * Gets the supply current limit configuration.
365 * @param currLimitConfigsToFill Configuration object to fill with read values.
366 * @param timeoutMs
367 * Timeout value in ms. If nonzero, function will wait for
368 * config success and report an error if it times out.
369 * @return Error Code generated by function. 0 indicates no error.
370 */
371 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
372 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
373 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
375 /**
376 * Gets the stator (output) current limit configuration.
377 * @param currLimitConfigsToFill Configuration object to fill with read values.
378 * @param timeoutMs
379 * Timeout value in ms. If nonzero, function will wait for
380 * config success and report an error if it times out.
381 * @return Error Code generated by function. 0 indicates no error.
382 */
383 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
384 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
385 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
387
388 //------ RAW Sensor API ----------//
389 /**
390 * @return object that can get/set individual RAW sensor values.
391 */
392 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
393 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
394 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
396
397 //------ Simulation API ----------//
398 /**
399 * @return object that can set simulation inputs.
400 */
401 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
402 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
403 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
405
406 //------ All Configs ----------//
407
408 /**
409 * Sets all PID persistant settings.
410 *
411 * @param pid Object with all of the PID set persistant settings
412 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
413 * @param timeoutMs
414 * Timeout value in ms. If nonzero, function will wait for
415 * config success and report an error if it times out.
416 * If zero, no blocking or checking is performed.
417 */
418 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
419 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
420 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
421 ctre::phoenix::ErrorCode ConfigurePID(const TalonFXPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
422 /**
423 * Gets all PID set persistant settings.
424 *
425 * @param pid Object with all of the PID set persistant settings
426 * @param pidIdx 0 for Primary closed-loop. 1 for auxiliary closed-loop.
427 * @param timeoutMs
428 * Timeout value in ms. If nonzero, function will wait for
429 * config success and report an error if it times out.
430 * If zero, no blocking or checking is performed.
431 */
432 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
433 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
434 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
435 void GetPIDConfigs(TalonFXPIDSetConfiguration& pid, int pidIdx = 0, int timeoutMs = 50);
436
437 /**
438 * Configures all persistent settings.
439 *
440 * @param allConfigs Object with all of the persistant settings
441 * @param timeoutMs
442 * Timeout value in ms. If nonzero, function will wait for
443 * config success and report an error if it times out.
444 * If zero, no blocking or checking is performed.
445 *
446 * @return Error Code generated by function. 0 indicates no error.
447 */
448 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
449 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
450 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
452 /**
453 * Gets all persistant settings.
454 *
455 * @param allConfigs Object with all of the persistant settings
456 * @param timeoutMs
457 * Timeout value in ms. If nonzero, function will wait for
458 * config success and report an error if it times out.
459 * If zero, no blocking or checking is performed.
460 */
461 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
462 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
463 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
464 void GetAllConfigs(TalonFXConfiguration& allConfigs, int timeoutMs = 50);
465 /**
466 * Configure the motor commutation type.
467 *
468 * @param motorCommutation Motor Commutation Type.
469 *
470 * @param timeoutMs
471 * Timeout value in ms. If nonzero, function will wait for config
472 * success and report an error if it times out. If zero, no
473 * blocking or checking is performed.
474 */
475 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
476 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
477 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
479 /**
480 * @param timeoutMs
481 * Timeout value in ms. If nonzero, function will wait for config
482 * success and report an error if it times out.
483 * @return The motor commutation type.
484 */
485 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
486 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
487 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
489
490 /**
491 * Sets the signage and range of the "Absolute Position" signal.
492 * Choose unsigned for an absolute range of [0,+1) rotations, [0,360) deg, etc...
493 * Choose signed for an absolute range of [-0.5,+0.5) rotations, [-180,+180) deg, etc...
494 * @param absoluteSensorRange
495 * Desired Sign/Range for the absolute position register.
496 * @param timeoutMs
497 * Timeout value in ms. If nonzero, function will wait for
498 * config success and report an error if it times out.
499 * If zero, no blocking or checking is performed.
500 * @return Error Code generated by function. 0 indicates no error.
501 */
502 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
503 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
504 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
506 /**
507 * Adjusts the zero point for the absolute position register.
508 * The absolute position of the sensor will always have a discontinuity (360 -> 0 deg) or (+180 -> -180)
509 * and a hard-limited mechanism may have such a discontinuity in its functional range.
510 * In which case use this config to move the discontinuity outside of the function range.
511 * @param offsetDegrees
512 * Offset in degrees (unit string and coefficient DO NOT apply for this config).
513 * @param timeoutMs
514 * Timeout value in ms. If nonzero, function will wait for
515 * config success and report an error if it times out.
516 * If zero, no blocking or checking is performed.
517 * @return Error Code generated by function. 0 indicates no error.
518 */
519 ErrorCode ConfigIntegratedSensorOffset(double offsetDegrees, int timeoutMs = 0);
520 /**
521 * Pick the strategy on how to initialize the integrated sensor absolute position register. Depending on the mechanism,
522 * it may be desirable to auto set the Position register to match the Absolute Position (swerve for example).
523 * Or it may be desired to zero the sensor on boot (drivetrain translation sensor or a relative servo).
524 *
525 * TIP: Tuner's self-test feature will report what the boot sensor value will be in the event the product is reset.
526 *
527 * @param initializationStrategy
528 * The sensor initialization strategy to use. This will impact the behavior the next time product boots up.
529 * @param timeoutMs
530 * Timeout value in ms. If nonzero, function will wait for
531 * config success and report an error if it times out.
532 * If zero, no blocking or checking is performed.
533 * @return Error Code generated by function. 0 indicates no error.
534 */
535 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
536 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
537 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
539
540 /* ----- virtual re-directs ------- */
541 virtual void Set(ControlMode mode, double value);
542 virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1);
543 virtual void SetInverted(InvertType invertType);
544 virtual void SetInverted(bool bInvert);
545 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
546 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
547 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
548 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
549 [[deprecated("This device's Phoenix 5 API is deprecated for removal in the 2025 season."
550 "Users should update to Phoenix 6 firmware and migrate to the Phoenix 6 API."
551 "A migration guide is available at https://v6.docs.ctr-electronics.com/en/stable/docs/migration/migration-guide/index.html")]]
552 virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx = 0, int timeoutMs = 0);
553
554 };// class TalonFX
555
556 } // namespace can
557 } // namespace motorcontrol
558 } // namespace phoenix
559} // namespace ctre
560
561#if defined(WIN32) || defined(_WIN32) || defined(_WIN64)
562#pragma warning (pop)
563#endif
Collection of sensors available to the Talon FX.
Definition: TalonFXSensorCollection.h:40
Collection of simulation commands available to a TalonFX motor controller.
Definition: TalonFXSimCollection.h:35
Util class to help with talon configs.
Definition: BaseTalon.h:230
CTRE Talon SRX Motor Controller when used on CAN Bus.
Definition: BaseTalon.h:267
Util class to help with talon configs.
Definition: TalonFX.h:139
static bool InitializationStrategyDifferent(const TalonFXConfiguration &settings)
Definition: TalonFX.h:172
static bool StatorCurrentDurationDifferent(const TalonFXConfiguration &settings)
Definition: TalonFX.h:156
static bool IntegratedSensorOffsetDegreesDifferent(const TalonFXConfiguration &settings)
Definition: TalonFX.h:168
static bool SupplyCurrentLimitDifferent(const TalonFXConfiguration &settings)
Determine if specified value is different from default.
Definition: TalonFX.h:152
static bool AbsoluteSensorRangeDifferent(const TalonFXConfiguration &settings)
Definition: TalonFX.h:164
static bool MotorCommutationDifferent(const TalonFXConfiguration &settings)
Definition: TalonFX.h:160
CTRE Talon FX Motor Controller when used on CAN Bus.
Definition: TalonFX.h:219
ctre::phoenix::ErrorCode ConfigGetSupplyCurrentLimit(ctre::phoenix::motorcontrol::SupplyCurrentLimitConfiguration &currLimitConfigsToFill, int timeoutMs=50)
Gets the supply current limit configuration.
ctre::phoenix::motorcontrol::TalonFXSimCollection & GetSimCollection()
ErrorCode ConfigIntegratedSensorInitializationStrategy(ctre::phoenix::sensors::SensorInitializationStrategy initializationStrategy, int timeoutMs=0)
Pick the strategy on how to initialize the integrated sensor absolute position register.
ErrorCode ConfigIntegratedSensorOffset(double offsetDegrees, int timeoutMs=0)
Adjusts the zero point for the absolute position register.
void Set(TalonFXControlMode mode, double demand0, DemandType demand1Type, double demand1)
ctre::phoenix::ErrorCode ConfigAllSettings(const TalonFXConfiguration &allConfigs, int timeoutMs=50)
Configures all persistent settings.
void GetAllConfigs(TalonFXConfiguration &allConfigs, int timeoutMs=50)
Gets all persistant settings.
ErrorCode ConfigIntegratedSensorAbsoluteRange(ctre::phoenix::sensors::AbsoluteSensorRange absoluteSensorRange, int timeoutMs=0)
Sets the signage and range of the "Absolute Position" signal.
ctre::phoenix::ErrorCode ConfigStatorCurrentLimit(const ctre::phoenix::motorcontrol::StatorCurrentLimitConfiguration &currLimitConfigs, int timeoutMs=50)
Configures the stator (output) current limit.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(RemoteFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
virtual void SetInverted(bool bInvert)
Inverts the hbridge output of the motor controller.
TalonFX & operator=(TalonFX const &)=delete
TalonFX(int deviceNumber, std::string const &canbus="")
Constructor for a Talon.
virtual ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(FeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the remote feedback device for the motor controller.
void GetPIDConfigs(TalonFXPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
Gets all PID set persistant settings.
ctre::phoenix::ErrorCode ConfigGetStatorCurrentLimit(ctre::phoenix::motorcontrol::StatorCurrentLimitConfiguration &currLimitConfigsToFill, int timeoutMs=50)
Gets the stator (output) current limit configuration.
virtual void Set(ControlMode mode, double demand0, DemandType demand1Type, double demand1)
void SetInverted(TalonFXInvertType invertType)
Inverts the hbridge output of the motor controller in relation to the master if present.
void Set(TalonFXControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
virtual void Set(ControlMode mode, double value)
Sets the appropriate output on the talon, depending on the mode.
ctre::phoenix::ErrorCode ConfigSupplyCurrentLimit(const ctre::phoenix::motorcontrol::SupplyCurrentLimitConfiguration &currLimitConfigs, int timeoutMs=50)
Configures the supply-side current limit.
ctre::phoenix::ErrorCode ConfigSelectedFeedbackSensor(TalonFXFeedbackDevice feedbackDevice, int pidIdx=0, int timeoutMs=0)
Select the feedback device for the motor controller.
ctre::phoenix::ErrorCode ConfigMotorCommutation(ctre::phoenix::motorcontrol::MotorCommutation motorCommutation, int timeoutMs=0)
Configure the motor commutation type.
ctre::phoenix::ErrorCode ConfigGetMotorCommutation(ctre::phoenix::motorcontrol::MotorCommutation &motorCommutation, int timeoutMs=0)
ctre::phoenix::ErrorCode ConfigurePID(const TalonFXPIDSetConfiguration &pid, int pidIdx=0, int timeoutMs=50)
Sets all PID persistant settings.
virtual void SetInverted(InvertType invertType)
Inverts the hbridge output of the motor controller in relation to the master if present.
ctre::phoenix::motorcontrol::TalonFXSensorCollection & GetSensorCollection()
ControlMode
Choose the control mode for a motor controller.
Definition: ControlMode.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
TalonFXFeedbackDevice
Choose the feedback device for a Talon FX/Falcon 500.
Definition: FeedbackDevice.h:144
MotorCommutation
Choose the type of motor commutation.
Definition: MotorCommutation.h:20
RemoteFeedbackDevice
Choose the remote feedback device for a motor controller.
Definition: FeedbackDevice.h:179
FeedbackDevice
Choose the feedback device for a motor controller.
Definition: FeedbackDevice.h:14
@ IntegratedSensor
TalonFX supports an integrated sensor.
TalonFXControlMode
Choose the control mode for a TalonFX / Falcon 500.
Definition: ControlMode.h:68
TalonFXInvertType
Choose the invert type for a Talon FX based integrated motor controller.
Definition: InvertType.h:37
SensorInitializationStrategy
Enum for how CANCoder should initialize its position register on boot.
Definition: SensorInitializationStrategy.h:22
@ BootToZero
On boot up, set position to zero.
Definition: SensorInitializationStrategy.h:26
AbsoluteSensorRange
Enum for how to range the absolute sensor position.
Definition: AbsoluteSensorRange.h:22
@ Unsigned_0_to_360
Express the absolute position as an unsigned value.
Definition: AbsoluteSensorRange.h:27
ErrorCode
Definition: ErrorCode.h:13
namespace ctre
Definition: paramEnum.h:5
bool enableOptimizations
Enable optimizations for ConfigAll (defaults true)
Definition: CustomParamConfiguration.h:23
Describes the desired stator current limiting behavior.
Definition: StatorCurrentLimitConfiguration.h:22
bool Equals(const StatorCurrentLimitConfiguration &rhs) const
Definition: StatorCurrentLimitConfiguration.h:109
std::string ToString() const
Definition: StatorCurrentLimitConfiguration.h:62
Describes the desired stator current limiting behavior.
Definition: SupplyCurrentLimitConfiguration.h:13
std::string ToString() const
Definition: SupplyCurrentLimitConfiguration.h:53
bool Equals(const SupplyCurrentLimitConfiguration &rhs) const
Definition: SupplyCurrentLimitConfiguration.h:100
Configurables available to BaseTalon.
Definition: BaseTalon.h:96
std::string toString()
Definition: BaseTalon.h:197
Configurables available to BaseTalon's PID.
Definition: BaseTalon.h:34
Configurables available to TalonFX.
Definition: TalonFX.h:50
ctre::phoenix::motorcontrol::MotorCommutation motorCommutation
Choose the type of motor commutation.
Definition: TalonFX.h:64
std::string toString(std::string prependString)
Definition: TalonFX.h:109
ctre::phoenix::sensors::SensorInitializationStrategy initializationStrategy
The sensor initialization strategy to use.This will impact the behavior the next time device boots up...
Definition: TalonFX.h:88
double integratedSensorOffsetDegrees
Adjusts the zero point for the absolute position register.
Definition: TalonFX.h:78
ctre::phoenix::sensors::AbsoluteSensorRange absoluteSensorRange
Desired Sign / Range for the absolute position register.
Definition: TalonFX.h:71
SupplyCurrentLimitConfiguration supplyCurrLimit
Supply-side current limiting.
Definition: TalonFX.h:55
std::string toString()
Definition: TalonFX.h:100
StatorCurrentLimitConfiguration statorCurrLimit
Stator-side current limiting.
Definition: TalonFX.h:59
Configurables available to TalonFX's PID.
Definition: TalonFX.h:36