Loading [MathJax]/extensions/tex2jax.js
CTRE Phoenix 6 C++ 25.3.2
All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Configs.hpp
Go to the documentation of this file.
1/*
2 * Copyright (C) Cross The Road Electronics.  All rights reserved.
3 * License information can be found in CTRE_LICENSE.txt
4 * For support and suggestions contact support@ctr-electronics.com or file
5 * an issue tracker at https://github.com/CrossTheRoadElec/Phoenix-Releases
6 */
7#pragma once
8
14#include "ctre/unit/pid_ff.h"
15#include <units/angle.h>
16#include <units/angular_acceleration.h>
17#include <units/angular_jerk.h>
18#include <units/angular_velocity.h>
19#include <units/current.h>
20#include <units/dimensionless.h>
21#include <units/frequency.h>
22#include <units/length.h>
23#include <units/voltage.h>
24#include <sstream>
25#include <map>
26#include <string>
27
28namespace ctre {
29namespace phoenix6 {
30
31namespace hardware { namespace core { class CoreCANcoder; } }
32namespace hardware { namespace core { class CoreCANdi; } }
33namespace hardware { namespace core { class CoreTalonFX; } }
34namespace hardware { namespace core { class CoreCANrange; } }
35namespace configs { class SlotConfigs; }
36
37namespace configs {
38
40{
41public:
42 virtual std::string ToString() const = 0;
43 friend std::ostream &operator<<(std::ostream &str, const ParentConfiguration &v)
44 {
45 str << v.ToString();
46 return str;
47 }
48 virtual ctre::phoenix::StatusCode Deserialize(const std::string &string) = 0;
49};
50
51
52/**
53 * \brief Configs that affect the magnet sensor and how to interpret
54 * it.
55 *
56 * \details Includes sensor direction, the sensor discontinuity point,
57 * and the magnet offset.
58 */
60{
61public:
62 constexpr MagnetSensorConfigs() = default;
63
64 /**
65 * \brief Direction of the sensor to determine positive rotation, as
66 * seen facing the LED side of the CANcoder.
67 *
68 */
70 /**
71 * \brief This offset is added to the reported position, allowing the
72 * application to trim the zero position. When set to the default
73 * value of zero, position reports zero when magnet north pole aligns
74 * with the LED.
75 *
76 * - Minimum Value: -1
77 * - Maximum Value: 1
78 * - Default Value: 0
79 * - Units: rotations
80 */
81 units::angle::turn_t MagnetOffset = 0_tr;
82 /**
83 * \brief The positive discontinuity point of the absolute sensor in
84 * rotations. This determines the point at which the absolute sensor
85 * wraps around, keeping the absolute position in the range [x-1, x).
86 *
87 * - Setting this to 1 makes the absolute position unsigned [0, 1)
88 * - Setting this to 0.5 makes the absolute position signed [-0.5,
89 * 0.5)
90 * - Setting this to 0 makes the absolute position always negative
91 * [-1, 0)
92 *
93 * Many rotational mechanisms such as arms have a region of motion
94 * that is unreachable. This should be set to the center of that
95 * region of motion, in non-negative rotations. This affects the
96 * position of the device at bootup.
97 *
98 * \details For example, consider an arm which can travel from -0.2 to
99 * 0.6 rotations with a little leeway, where 0 is horizontally
100 * forward. Since -0.2 rotations has the same absolute position as 0.8
101 * rotations, we can say that the arm typically does not travel in the
102 * range (0.6, 0.8) rotations. As a result, the discontinuity point
103 * would be the center of that range, which is 0.7 rotations. This
104 * results in an absolute sensor range of [-0.3, 0.7) rotations.
105 *
106 * On a Talon motor controller, this is only supported when using the
107 * PulseWidth sensor source.
108 *
109 * - Minimum Value: 0.0
110 * - Maximum Value: 1.0
111 * - Default Value: 0.5
112 * - Units: rotations
113 */
114 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
115
116 /**
117 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
118 * method-chaining and easier to use config API.
119 *
120 * Direction of the sensor to determine positive rotation, as seen
121 * facing the LED side of the CANcoder.
122 *
123 *
124 * \param newSensorDirection Parameter to modify
125 * \returns Itself
126 */
128 {
129 SensorDirection = std::move(newSensorDirection);
130 return *this;
131 }
132
133 /**
134 * \brief Modifies this configuration's MagnetOffset parameter and returns itself for
135 * method-chaining and easier to use config API.
136 *
137 * This offset is added to the reported position, allowing the
138 * application to trim the zero position. When set to the default
139 * value of zero, position reports zero when magnet north pole aligns
140 * with the LED.
141 *
142 * - Minimum Value: -1
143 * - Maximum Value: 1
144 * - Default Value: 0
145 * - Units: rotations
146 *
147 * \param newMagnetOffset Parameter to modify
148 * \returns Itself
149 */
150 constexpr MagnetSensorConfigs &WithMagnetOffset(units::angle::turn_t newMagnetOffset)
151 {
152 MagnetOffset = std::move(newMagnetOffset);
153 return *this;
154 }
155
156 /**
157 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
158 * method-chaining and easier to use config API.
159 *
160 * The positive discontinuity point of the absolute sensor in
161 * rotations. This determines the point at which the absolute sensor
162 * wraps around, keeping the absolute position in the range [x-1, x).
163 *
164 * - Setting this to 1 makes the absolute position unsigned [0, 1)
165 * - Setting this to 0.5 makes the absolute position signed [-0.5,
166 * 0.5)
167 * - Setting this to 0 makes the absolute position always negative
168 * [-1, 0)
169 *
170 * Many rotational mechanisms such as arms have a region of motion
171 * that is unreachable. This should be set to the center of that
172 * region of motion, in non-negative rotations. This affects the
173 * position of the device at bootup.
174 *
175 * \details For example, consider an arm which can travel from -0.2 to
176 * 0.6 rotations with a little leeway, where 0 is horizontally
177 * forward. Since -0.2 rotations has the same absolute position as 0.8
178 * rotations, we can say that the arm typically does not travel in the
179 * range (0.6, 0.8) rotations. As a result, the discontinuity point
180 * would be the center of that range, which is 0.7 rotations. This
181 * results in an absolute sensor range of [-0.3, 0.7) rotations.
182 *
183 * On a Talon motor controller, this is only supported when using the
184 * PulseWidth sensor source.
185 *
186 * - Minimum Value: 0.0
187 * - Maximum Value: 1.0
188 * - Default Value: 0.5
189 * - Units: rotations
190 *
191 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
192 * \returns Itself
193 */
194 constexpr MagnetSensorConfigs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
195 {
196 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
197 return *this;
198 }
199
200
201
202 std::string ToString() const override
203 {
204 std::stringstream ss;
205 ss << "Config Group: MagnetSensor" << std::endl;
206 ss << " SensorDirection: " << SensorDirection << std::endl;
207 ss << " MagnetOffset: " << MagnetOffset.to<double>() << " rotations" << std::endl;
208 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
209 return ss.str();
210 }
211
212 std::string Serialize() const override
213 {
214 std::stringstream ss;
215 char *ref;
216 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANcoder_SensorDirection, SensorDirection.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
217 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANCoder_MagnetOffset, MagnetOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
218 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
219 return ss.str();
220 }
221
222 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
223 {
224 const char *string_c_str = to_deserialize.c_str();
225 size_t string_length = to_deserialize.length();
226 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANcoder_SensorDirection, string_c_str, string_length, &SensorDirection.value);
227 double MagnetOffsetVal = MagnetOffset.to<double>();
228 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANCoder_MagnetOffset, string_c_str, string_length, &MagnetOffsetVal);
229 MagnetOffset = units::angle::turn_t{MagnetOffsetVal};
230 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
231 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
232 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
233 return 0;
234 }
235};
236
237
238/**
239 * \brief Configs for Pigeon 2's Mount Pose configuration.
240 *
241 * \details These configs allow the Pigeon2 to be mounted in whatever
242 * orientation that's desired and ensure the reported
243 * Yaw/Pitch/Roll is from the robot's reference.
244 */
246{
247public:
248 constexpr MountPoseConfigs() = default;
249
250 /**
251 * \brief The mounting calibration yaw-component.
252 *
253 * - Minimum Value: -360
254 * - Maximum Value: 360
255 * - Default Value: 0
256 * - Units: deg
257 */
258 units::angle::degree_t MountPoseYaw = 0_deg;
259 /**
260 * \brief The mounting calibration pitch-component.
261 *
262 * - Minimum Value: -360
263 * - Maximum Value: 360
264 * - Default Value: 0
265 * - Units: deg
266 */
267 units::angle::degree_t MountPosePitch = 0_deg;
268 /**
269 * \brief The mounting calibration roll-component.
270 *
271 * - Minimum Value: -360
272 * - Maximum Value: 360
273 * - Default Value: 0
274 * - Units: deg
275 */
276 units::angle::degree_t MountPoseRoll = 0_deg;
277
278 /**
279 * \brief Modifies this configuration's MountPoseYaw parameter and returns itself for
280 * method-chaining and easier to use config API.
281 *
282 * The mounting calibration yaw-component.
283 *
284 * - Minimum Value: -360
285 * - Maximum Value: 360
286 * - Default Value: 0
287 * - Units: deg
288 *
289 * \param newMountPoseYaw Parameter to modify
290 * \returns Itself
291 */
292 constexpr MountPoseConfigs &WithMountPoseYaw(units::angle::degree_t newMountPoseYaw)
293 {
294 MountPoseYaw = std::move(newMountPoseYaw);
295 return *this;
296 }
297
298 /**
299 * \brief Modifies this configuration's MountPosePitch parameter and returns itself for
300 * method-chaining and easier to use config API.
301 *
302 * The mounting calibration pitch-component.
303 *
304 * - Minimum Value: -360
305 * - Maximum Value: 360
306 * - Default Value: 0
307 * - Units: deg
308 *
309 * \param newMountPosePitch Parameter to modify
310 * \returns Itself
311 */
312 constexpr MountPoseConfigs &WithMountPosePitch(units::angle::degree_t newMountPosePitch)
313 {
314 MountPosePitch = std::move(newMountPosePitch);
315 return *this;
316 }
317
318 /**
319 * \brief Modifies this configuration's MountPoseRoll parameter and returns itself for
320 * method-chaining and easier to use config API.
321 *
322 * The mounting calibration roll-component.
323 *
324 * - Minimum Value: -360
325 * - Maximum Value: 360
326 * - Default Value: 0
327 * - Units: deg
328 *
329 * \param newMountPoseRoll Parameter to modify
330 * \returns Itself
331 */
332 constexpr MountPoseConfigs &WithMountPoseRoll(units::angle::degree_t newMountPoseRoll)
333 {
334 MountPoseRoll = std::move(newMountPoseRoll);
335 return *this;
336 }
337
338
339
340 std::string ToString() const override
341 {
342 std::stringstream ss;
343 ss << "Config Group: MountPose" << std::endl;
344 ss << " MountPoseYaw: " << MountPoseYaw.to<double>() << " deg" << std::endl;
345 ss << " MountPosePitch: " << MountPosePitch.to<double>() << " deg" << std::endl;
346 ss << " MountPoseRoll: " << MountPoseRoll.to<double>() << " deg" << std::endl;
347 return ss.str();
348 }
349
350 std::string Serialize() const override
351 {
352 std::stringstream ss;
353 char *ref;
354 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPoseYaw, MountPoseYaw.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
355 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPosePitch, MountPosePitch.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
356 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPoseRoll, MountPoseRoll.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
357 return ss.str();
358 }
359
360 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
361 {
362 const char *string_c_str = to_deserialize.c_str();
363 size_t string_length = to_deserialize.length();
364 double MountPoseYawVal = MountPoseYaw.to<double>();
365 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPoseYaw, string_c_str, string_length, &MountPoseYawVal);
366 MountPoseYaw = units::angle::degree_t{MountPoseYawVal};
367 double MountPosePitchVal = MountPosePitch.to<double>();
368 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPosePitch, string_c_str, string_length, &MountPosePitchVal);
369 MountPosePitch = units::angle::degree_t{MountPosePitchVal};
370 double MountPoseRollVal = MountPoseRoll.to<double>();
371 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2MountPoseRoll, string_c_str, string_length, &MountPoseRollVal);
372 MountPoseRoll = units::angle::degree_t{MountPoseRollVal};
373 return 0;
374 }
375};
376
377
378/**
379 * \brief Configs to trim the Pigeon2's gyroscope.
380 *
381 * \details Pigeon2 allows the user to trim the gyroscope's
382 * sensitivity. While this isn't necessary for the Pigeon2,
383 * as it comes calibrated out-of-the-box, users can make use
384 * of this to make the Pigeon2 even more accurate for their
385 * application.
386 */
388{
389public:
390 constexpr GyroTrimConfigs() = default;
391
392 /**
393 * \brief The gyro scalar component for the X axis.
394 *
395 * - Minimum Value: -180
396 * - Maximum Value: 180
397 * - Default Value: 0
398 * - Units: deg per rotation
399 */
400 units::dimensionless::scalar_t GyroScalarX = 0;
401 /**
402 * \brief The gyro scalar component for the Y axis.
403 *
404 * - Minimum Value: -180
405 * - Maximum Value: 180
406 * - Default Value: 0
407 * - Units: deg per rotation
408 */
409 units::dimensionless::scalar_t GyroScalarY = 0;
410 /**
411 * \brief The gyro scalar component for the Z axis.
412 *
413 * - Minimum Value: -180
414 * - Maximum Value: 180
415 * - Default Value: 0
416 * - Units: deg per rotation
417 */
418 units::dimensionless::scalar_t GyroScalarZ = 0;
419
420 /**
421 * \brief Modifies this configuration's GyroScalarX parameter and returns itself for
422 * method-chaining and easier to use config API.
423 *
424 * The gyro scalar component for the X axis.
425 *
426 * - Minimum Value: -180
427 * - Maximum Value: 180
428 * - Default Value: 0
429 * - Units: deg per rotation
430 *
431 * \param newGyroScalarX Parameter to modify
432 * \returns Itself
433 */
434 constexpr GyroTrimConfigs &WithGyroScalarX(units::dimensionless::scalar_t newGyroScalarX)
435 {
436 GyroScalarX = std::move(newGyroScalarX);
437 return *this;
438 }
439
440 /**
441 * \brief Modifies this configuration's GyroScalarY parameter and returns itself for
442 * method-chaining and easier to use config API.
443 *
444 * The gyro scalar component for the Y axis.
445 *
446 * - Minimum Value: -180
447 * - Maximum Value: 180
448 * - Default Value: 0
449 * - Units: deg per rotation
450 *
451 * \param newGyroScalarY Parameter to modify
452 * \returns Itself
453 */
454 constexpr GyroTrimConfigs &WithGyroScalarY(units::dimensionless::scalar_t newGyroScalarY)
455 {
456 GyroScalarY = std::move(newGyroScalarY);
457 return *this;
458 }
459
460 /**
461 * \brief Modifies this configuration's GyroScalarZ parameter and returns itself for
462 * method-chaining and easier to use config API.
463 *
464 * The gyro scalar component for the Z axis.
465 *
466 * - Minimum Value: -180
467 * - Maximum Value: 180
468 * - Default Value: 0
469 * - Units: deg per rotation
470 *
471 * \param newGyroScalarZ Parameter to modify
472 * \returns Itself
473 */
474 constexpr GyroTrimConfigs &WithGyroScalarZ(units::dimensionless::scalar_t newGyroScalarZ)
475 {
476 GyroScalarZ = std::move(newGyroScalarZ);
477 return *this;
478 }
479
480
481
482 std::string ToString() const override
483 {
484 std::stringstream ss;
485 ss << "Config Group: GyroTrim" << std::endl;
486 ss << " GyroScalarX: " << GyroScalarX.to<double>() << " deg per rotation" << std::endl;
487 ss << " GyroScalarY: " << GyroScalarY.to<double>() << " deg per rotation" << std::endl;
488 ss << " GyroScalarZ: " << GyroScalarZ.to<double>() << " deg per rotation" << std::endl;
489 return ss.str();
490 }
491
492 std::string Serialize() const override
493 {
494 std::stringstream ss;
495 char *ref;
496 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarX, GyroScalarX.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
497 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarY, GyroScalarY.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
498 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarZ, GyroScalarZ.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
499 return ss.str();
500 }
501
502 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
503 {
504 const char *string_c_str = to_deserialize.c_str();
505 size_t string_length = to_deserialize.length();
506 double GyroScalarXVal = GyroScalarX.to<double>();
507 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarX, string_c_str, string_length, &GyroScalarXVal);
508 GyroScalarX = units::dimensionless::scalar_t{GyroScalarXVal};
509 double GyroScalarYVal = GyroScalarY.to<double>();
510 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarY, string_c_str, string_length, &GyroScalarYVal);
511 GyroScalarY = units::dimensionless::scalar_t{GyroScalarYVal};
512 double GyroScalarZVal = GyroScalarZ.to<double>();
513 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Pigeon2GyroScalarZ, string_c_str, string_length, &GyroScalarZVal);
514 GyroScalarZ = units::dimensionless::scalar_t{GyroScalarZVal};
515 return 0;
516 }
517};
518
519
520/**
521 * \brief Configs to enable/disable various features of the Pigeon2.
522 *
523 * \details These configs allow the user to enable or disable various
524 * aspects of the Pigeon2.
525 */
527{
528public:
529 constexpr Pigeon2FeaturesConfigs() = default;
530
531 /**
532 * \brief Turns on or off the magnetometer fusing for 9-axis. FRC
533 * users are not recommended to turn this on, as the magnetic
534 * influence of the robot will likely negatively affect the
535 * performance of the Pigeon2.
536 *
537 * - Default Value: False
538 */
539 bool EnableCompass = false;
540 /**
541 * \brief Disables using the temperature compensation feature.
542 *
543 * - Default Value: False
544 */
546 /**
547 * \brief Disables using the no-motion calibration feature.
548 *
549 * - Default Value: False
550 */
552
553 /**
554 * \brief Modifies this configuration's EnableCompass parameter and returns itself for
555 * method-chaining and easier to use config API.
556 *
557 * Turns on or off the magnetometer fusing for 9-axis. FRC users are
558 * not recommended to turn this on, as the magnetic influence of the
559 * robot will likely negatively affect the performance of the Pigeon2.
560 *
561 * - Default Value: False
562 *
563 * \param newEnableCompass Parameter to modify
564 * \returns Itself
565 */
566 constexpr Pigeon2FeaturesConfigs &WithEnableCompass(bool newEnableCompass)
567 {
568 EnableCompass = std::move(newEnableCompass);
569 return *this;
570 }
571
572 /**
573 * \brief Modifies this configuration's DisableTemperatureCompensation parameter and returns itself for
574 * method-chaining and easier to use config API.
575 *
576 * Disables using the temperature compensation feature.
577 *
578 * - Default Value: False
579 *
580 * \param newDisableTemperatureCompensation Parameter to modify
581 * \returns Itself
582 */
583 constexpr Pigeon2FeaturesConfigs &WithDisableTemperatureCompensation(bool newDisableTemperatureCompensation)
584 {
585 DisableTemperatureCompensation = std::move(newDisableTemperatureCompensation);
586 return *this;
587 }
588
589 /**
590 * \brief Modifies this configuration's DisableNoMotionCalibration parameter and returns itself for
591 * method-chaining and easier to use config API.
592 *
593 * Disables using the no-motion calibration feature.
594 *
595 * - Default Value: False
596 *
597 * \param newDisableNoMotionCalibration Parameter to modify
598 * \returns Itself
599 */
600 constexpr Pigeon2FeaturesConfigs &WithDisableNoMotionCalibration(bool newDisableNoMotionCalibration)
601 {
602 DisableNoMotionCalibration = std::move(newDisableNoMotionCalibration);
603 return *this;
604 }
605
606
607
608 std::string ToString() const override
609 {
610 std::stringstream ss;
611 ss << "Config Group: Pigeon2Features" << std::endl;
612 ss << " EnableCompass: " << EnableCompass << std::endl;
613 ss << " DisableTemperatureCompensation: " << DisableTemperatureCompensation << std::endl;
614 ss << " DisableNoMotionCalibration: " << DisableNoMotionCalibration << std::endl;
615 return ss.str();
616 }
617
618 std::string Serialize() const override
619 {
620 std::stringstream ss;
621 char *ref;
622 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2UseCompass, EnableCompass, &ref); if (ref != nullptr) { ss << ref; free(ref); }
623 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2DisableTemperatureCompensation, DisableTemperatureCompensation, &ref); if (ref != nullptr) { ss << ref; free(ref); }
624 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2DisableNoMotionCalibration, DisableNoMotionCalibration, &ref); if (ref != nullptr) { ss << ref; free(ref); }
625 return ss.str();
626 }
627
628 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
629 {
630 const char *string_c_str = to_deserialize.c_str();
631 size_t string_length = to_deserialize.length();
632 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2UseCompass, string_c_str, string_length, &EnableCompass);
633 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2DisableTemperatureCompensation, string_c_str, string_length, &DisableTemperatureCompensation);
634 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Pigeon2DisableNoMotionCalibration, string_c_str, string_length, &DisableNoMotionCalibration);
635 return 0;
636 }
637};
638
639
640/**
641 * \brief Configs that directly affect motor output.
642 *
643 * \details Includes motor invert, neutral mode, and other features
644 * related to motor output.
645 */
647{
648public:
649 constexpr MotorOutputConfigs() = default;
650
651 /**
652 * \brief Invert state of the device as seen from the front of the
653 * motor.
654 *
655 */
657 /**
658 * \brief The state of the motor controller bridge when output is
659 * neutral or disabled.
660 *
661 */
663 /**
664 * \brief Configures the output deadband duty cycle during duty cycle
665 * and voltage based control modes.
666 *
667 * - Minimum Value: 0.0
668 * - Maximum Value: 0.25
669 * - Default Value: 0
670 * - Units: fractional
671 */
672 units::dimensionless::scalar_t DutyCycleNeutralDeadband = 0;
673 /**
674 * \brief Maximum (forward) output during duty cycle based control
675 * modes.
676 *
677 * - Minimum Value: -1.0
678 * - Maximum Value: 1.0
679 * - Default Value: 1
680 * - Units: fractional
681 */
682 units::dimensionless::scalar_t PeakForwardDutyCycle = 1;
683 /**
684 * \brief Minimum (reverse) output during duty cycle based control
685 * modes.
686 *
687 * - Minimum Value: -1.0
688 * - Maximum Value: 1.0
689 * - Default Value: -1
690 * - Units: fractional
691 */
692 units::dimensionless::scalar_t PeakReverseDutyCycle = -1;
693 /**
694 * \brief When a control request UseTimesync is enabled, this
695 * determines the time-sychronized frequency at which control requests
696 * are applied.
697 *
698 * \details The application of the control request will be delayed
699 * until the next timesync boundary at the frequency defined by this
700 * config. When set to 0 Hz, timesync will never be used for control
701 * requests, regardless of the value of UseTimesync.
702 *
703 * - Minimum Value: 50
704 * - Maximum Value: 500
705 * - Default Value: 0
706 * - Units: Hz
707 */
708 units::frequency::hertz_t ControlTimesyncFreqHz = 0_Hz;
709
710 /**
711 * \brief Modifies this configuration's Inverted parameter and returns itself for
712 * method-chaining and easier to use config API.
713 *
714 * Invert state of the device as seen from the front of the motor.
715 *
716 *
717 * \param newInverted Parameter to modify
718 * \returns Itself
719 */
721 {
722 Inverted = std::move(newInverted);
723 return *this;
724 }
725
726 /**
727 * \brief Modifies this configuration's NeutralMode parameter and returns itself for
728 * method-chaining and easier to use config API.
729 *
730 * The state of the motor controller bridge when output is neutral or
731 * disabled.
732 *
733 *
734 * \param newNeutralMode Parameter to modify
735 * \returns Itself
736 */
738 {
739 NeutralMode = std::move(newNeutralMode);
740 return *this;
741 }
742
743 /**
744 * \brief Modifies this configuration's DutyCycleNeutralDeadband parameter and returns itself for
745 * method-chaining and easier to use config API.
746 *
747 * Configures the output deadband duty cycle during duty cycle and
748 * voltage based control modes.
749 *
750 * - Minimum Value: 0.0
751 * - Maximum Value: 0.25
752 * - Default Value: 0
753 * - Units: fractional
754 *
755 * \param newDutyCycleNeutralDeadband Parameter to modify
756 * \returns Itself
757 */
758 constexpr MotorOutputConfigs &WithDutyCycleNeutralDeadband(units::dimensionless::scalar_t newDutyCycleNeutralDeadband)
759 {
760 DutyCycleNeutralDeadband = std::move(newDutyCycleNeutralDeadband);
761 return *this;
762 }
763
764 /**
765 * \brief Modifies this configuration's PeakForwardDutyCycle parameter and returns itself for
766 * method-chaining and easier to use config API.
767 *
768 * Maximum (forward) output during duty cycle based control modes.
769 *
770 * - Minimum Value: -1.0
771 * - Maximum Value: 1.0
772 * - Default Value: 1
773 * - Units: fractional
774 *
775 * \param newPeakForwardDutyCycle Parameter to modify
776 * \returns Itself
777 */
778 constexpr MotorOutputConfigs &WithPeakForwardDutyCycle(units::dimensionless::scalar_t newPeakForwardDutyCycle)
779 {
780 PeakForwardDutyCycle = std::move(newPeakForwardDutyCycle);
781 return *this;
782 }
783
784 /**
785 * \brief Modifies this configuration's PeakReverseDutyCycle parameter and returns itself for
786 * method-chaining and easier to use config API.
787 *
788 * Minimum (reverse) output during duty cycle based control modes.
789 *
790 * - Minimum Value: -1.0
791 * - Maximum Value: 1.0
792 * - Default Value: -1
793 * - Units: fractional
794 *
795 * \param newPeakReverseDutyCycle Parameter to modify
796 * \returns Itself
797 */
798 constexpr MotorOutputConfigs &WithPeakReverseDutyCycle(units::dimensionless::scalar_t newPeakReverseDutyCycle)
799 {
800 PeakReverseDutyCycle = std::move(newPeakReverseDutyCycle);
801 return *this;
802 }
803
804 /**
805 * \brief Modifies this configuration's ControlTimesyncFreqHz parameter and returns itself for
806 * method-chaining and easier to use config API.
807 *
808 * When a control request UseTimesync is enabled, this determines the
809 * time-sychronized frequency at which control requests are applied.
810 *
811 * \details The application of the control request will be delayed
812 * until the next timesync boundary at the frequency defined by this
813 * config. When set to 0 Hz, timesync will never be used for control
814 * requests, regardless of the value of UseTimesync.
815 *
816 * - Minimum Value: 50
817 * - Maximum Value: 500
818 * - Default Value: 0
819 * - Units: Hz
820 *
821 * \param newControlTimesyncFreqHz Parameter to modify
822 * \returns Itself
823 */
824 constexpr MotorOutputConfigs &WithControlTimesyncFreqHz(units::frequency::hertz_t newControlTimesyncFreqHz)
825 {
826 ControlTimesyncFreqHz = std::move(newControlTimesyncFreqHz);
827 return *this;
828 }
829
830
831
832 std::string ToString() const override
833 {
834 std::stringstream ss;
835 ss << "Config Group: MotorOutput" << std::endl;
836 ss << " Inverted: " << Inverted << std::endl;
837 ss << " NeutralMode: " << NeutralMode << std::endl;
838 ss << " DutyCycleNeutralDeadband: " << DutyCycleNeutralDeadband.to<double>() << " fractional" << std::endl;
839 ss << " PeakForwardDutyCycle: " << PeakForwardDutyCycle.to<double>() << " fractional" << std::endl;
840 ss << " PeakReverseDutyCycle: " << PeakReverseDutyCycle.to<double>() << " fractional" << std::endl;
841 ss << " ControlTimesyncFreqHz: " << ControlTimesyncFreqHz.to<double>() << " Hz" << std::endl;
842 return ss.str();
843 }
844
845 std::string Serialize() const override
846 {
847 std::stringstream ss;
848 char *ref;
849 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_Inverted, Inverted.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
850 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_NeutralMode, NeutralMode.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
851 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleNeutralDB, DutyCycleNeutralDeadband.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
852 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForwardDC, PeakForwardDutyCycle.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
853 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakReverseDC, PeakReverseDutyCycle.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
854 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ControlTimesyncFreq, ControlTimesyncFreqHz.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
855 return ss.str();
856 }
857
858 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
859 {
860 const char *string_c_str = to_deserialize.c_str();
861 size_t string_length = to_deserialize.length();
862 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_Inverted, string_c_str, string_length, &Inverted.value);
863 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_NeutralMode, string_c_str, string_length, &NeutralMode.value);
864 double DutyCycleNeutralDeadbandVal = DutyCycleNeutralDeadband.to<double>();
865 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleNeutralDB, string_c_str, string_length, &DutyCycleNeutralDeadbandVal);
866 DutyCycleNeutralDeadband = units::dimensionless::scalar_t{DutyCycleNeutralDeadbandVal};
867 double PeakForwardDutyCycleVal = PeakForwardDutyCycle.to<double>();
868 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForwardDC, string_c_str, string_length, &PeakForwardDutyCycleVal);
869 PeakForwardDutyCycle = units::dimensionless::scalar_t{PeakForwardDutyCycleVal};
870 double PeakReverseDutyCycleVal = PeakReverseDutyCycle.to<double>();
871 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakReverseDC, string_c_str, string_length, &PeakReverseDutyCycleVal);
872 PeakReverseDutyCycle = units::dimensionless::scalar_t{PeakReverseDutyCycleVal};
873 double ControlTimesyncFreqHzVal = ControlTimesyncFreqHz.to<double>();
874 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ControlTimesyncFreq, string_c_str, string_length, &ControlTimesyncFreqHzVal);
875 ControlTimesyncFreqHz = units::frequency::hertz_t{ControlTimesyncFreqHzVal};
876 return 0;
877 }
878};
879
880
881/**
882 * \brief Configs that directly affect current limiting features.
883 *
884 * \details Contains the supply/stator current limit thresholds and
885 * whether to enable them.
886 */
888{
889public:
890 constexpr CurrentLimitsConfigs() = default;
891
892 /**
893 * \brief The amount of current allowed in the motor (motoring and
894 * regen current). Note this requires StatorCurrentLimitEnable to be
895 * true.
896 *
897 * For torque current control, this is applied in addition to the
898 * PeakForwardTorqueCurrent and PeakReverseTorqueCurrent in
899 * TorqueCurrentConfigs.
900 *
901 * Stator current is directly proportional to torque, so this limit
902 * can be used to restrict the torque output of the motor, such as
903 * preventing wheel slip for a drivetrain. Additionally, stator
904 * current limits can prevent brownouts during acceleration; supply
905 * current will never exceed the stator current limit and is often
906 * significantly lower than stator current.
907 *
908 * A reasonable starting point for a stator current limit is 120 A,
909 * with values commonly ranging from 80-160 A. Mechanisms with a hard
910 * stop may need a smaller limit to reduce the torque applied when
911 * running into the hard stop.
912 *
913 * - Minimum Value: 0.0
914 * - Maximum Value: 800.0
915 * - Default Value: 120
916 * - Units: A
917 */
918 units::current::ampere_t StatorCurrentLimit = 120_A;
919 /**
920 * \brief Enable motor stator current limiting.
921 *
922 * - Default Value: True
923 */
925 /**
926 * \brief The absolute maximum amount of supply current allowed. Note
927 * this requires SupplyCurrentLimitEnable to be true. Use
928 * SupplyCurrentLowerLimit and SupplyCurrentLowerTime to reduce the
929 * supply current limit after the time threshold is exceeded.
930 *
931 * Supply current is the current drawn from the battery, so this limit
932 * can be used to prevent breaker trips and improve battery longevity.
933 * Additionally, in scenarios where the robot experiences brownouts
934 * despite configuring stator current limits, a supply current limit
935 * can further help avoid brownouts. However, it is important to note
936 * that such brownouts may be caused by a bad battery or poor power
937 * wiring.
938 *
939 * A reasonable starting point for a supply current limit is 70 A with
940 * a lower limit of 40 A after 1.0 second. Supply current limits
941 * commonly range from 20-80 A depending on the breaker used.
942 *
943 * - Minimum Value: 0.0
944 * - Maximum Value: 800.0
945 * - Default Value: 70
946 * - Units: A
947 */
948 units::current::ampere_t SupplyCurrentLimit = 70_A;
949 /**
950 * \brief Enable motor supply current limiting.
951 *
952 * - Default Value: True
953 */
955 /**
956 * \brief The amount of supply current allowed after the regular
957 * SupplyCurrentLimit is active for longer than
958 * SupplyCurrentLowerTime. This allows higher current draws for a
959 * fixed period of time before reducing the current limit to protect
960 * breakers. This has no effect if SupplyCurrentLimit is lower than
961 * this value or SupplyCurrentLowerTime is 0.
962 *
963 * - Minimum Value: 0.0
964 * - Maximum Value: 500
965 * - Default Value: 40
966 * - Units: A
967 */
968 units::current::ampere_t SupplyCurrentLowerLimit = 40_A;
969 /**
970 * \brief Reduces supply current to the SupplyCurrentLowerLimit after
971 * limiting to SupplyCurrentLimit for this period of time. If this is
972 * set to 0, SupplyCurrentLowerLimit will be ignored.
973 *
974 * - Minimum Value: 0.0
975 * - Maximum Value: 2.5
976 * - Default Value: 1.0
977 * - Units: seconds
978 */
979 units::time::second_t SupplyCurrentLowerTime = 1.0_s;
980
981 /**
982 * \brief Modifies this configuration's StatorCurrentLimit parameter and returns itself for
983 * method-chaining and easier to use config API.
984 *
985 * The amount of current allowed in the motor (motoring and regen
986 * current). Note this requires StatorCurrentLimitEnable to be true.
987 *
988 * For torque current control, this is applied in addition to the
989 * PeakForwardTorqueCurrent and PeakReverseTorqueCurrent in
990 * TorqueCurrentConfigs.
991 *
992 * Stator current is directly proportional to torque, so this limit
993 * can be used to restrict the torque output of the motor, such as
994 * preventing wheel slip for a drivetrain. Additionally, stator
995 * current limits can prevent brownouts during acceleration; supply
996 * current will never exceed the stator current limit and is often
997 * significantly lower than stator current.
998 *
999 * A reasonable starting point for a stator current limit is 120 A,
1000 * with values commonly ranging from 80-160 A. Mechanisms with a hard
1001 * stop may need a smaller limit to reduce the torque applied when
1002 * running into the hard stop.
1003 *
1004 * - Minimum Value: 0.0
1005 * - Maximum Value: 800.0
1006 * - Default Value: 120
1007 * - Units: A
1008 *
1009 * \param newStatorCurrentLimit Parameter to modify
1010 * \returns Itself
1011 */
1012 constexpr CurrentLimitsConfigs &WithStatorCurrentLimit(units::current::ampere_t newStatorCurrentLimit)
1013 {
1014 StatorCurrentLimit = std::move(newStatorCurrentLimit);
1015 return *this;
1016 }
1017
1018 /**
1019 * \brief Modifies this configuration's StatorCurrentLimitEnable parameter and returns itself for
1020 * method-chaining and easier to use config API.
1021 *
1022 * Enable motor stator current limiting.
1023 *
1024 * - Default Value: True
1025 *
1026 * \param newStatorCurrentLimitEnable Parameter to modify
1027 * \returns Itself
1028 */
1029 constexpr CurrentLimitsConfigs &WithStatorCurrentLimitEnable(bool newStatorCurrentLimitEnable)
1030 {
1031 StatorCurrentLimitEnable = std::move(newStatorCurrentLimitEnable);
1032 return *this;
1033 }
1034
1035 /**
1036 * \brief Modifies this configuration's SupplyCurrentLimit parameter and returns itself for
1037 * method-chaining and easier to use config API.
1038 *
1039 * The absolute maximum amount of supply current allowed. Note this
1040 * requires SupplyCurrentLimitEnable to be true. Use
1041 * SupplyCurrentLowerLimit and SupplyCurrentLowerTime to reduce the
1042 * supply current limit after the time threshold is exceeded.
1043 *
1044 * Supply current is the current drawn from the battery, so this limit
1045 * can be used to prevent breaker trips and improve battery longevity.
1046 * Additionally, in scenarios where the robot experiences brownouts
1047 * despite configuring stator current limits, a supply current limit
1048 * can further help avoid brownouts. However, it is important to note
1049 * that such brownouts may be caused by a bad battery or poor power
1050 * wiring.
1051 *
1052 * A reasonable starting point for a supply current limit is 70 A with
1053 * a lower limit of 40 A after 1.0 second. Supply current limits
1054 * commonly range from 20-80 A depending on the breaker used.
1055 *
1056 * - Minimum Value: 0.0
1057 * - Maximum Value: 800.0
1058 * - Default Value: 70
1059 * - Units: A
1060 *
1061 * \param newSupplyCurrentLimit Parameter to modify
1062 * \returns Itself
1063 */
1064 constexpr CurrentLimitsConfigs &WithSupplyCurrentLimit(units::current::ampere_t newSupplyCurrentLimit)
1065 {
1066 SupplyCurrentLimit = std::move(newSupplyCurrentLimit);
1067 return *this;
1068 }
1069
1070 /**
1071 * \brief Modifies this configuration's SupplyCurrentLimitEnable parameter and returns itself for
1072 * method-chaining and easier to use config API.
1073 *
1074 * Enable motor supply current limiting.
1075 *
1076 * - Default Value: True
1077 *
1078 * \param newSupplyCurrentLimitEnable Parameter to modify
1079 * \returns Itself
1080 */
1081 constexpr CurrentLimitsConfigs &WithSupplyCurrentLimitEnable(bool newSupplyCurrentLimitEnable)
1082 {
1083 SupplyCurrentLimitEnable = std::move(newSupplyCurrentLimitEnable);
1084 return *this;
1085 }
1086
1087 /**
1088 * \brief Modifies this configuration's SupplyCurrentLowerLimit parameter and returns itself for
1089 * method-chaining and easier to use config API.
1090 *
1091 * The amount of supply current allowed after the regular
1092 * SupplyCurrentLimit is active for longer than
1093 * SupplyCurrentLowerTime. This allows higher current draws for a
1094 * fixed period of time before reducing the current limit to protect
1095 * breakers. This has no effect if SupplyCurrentLimit is lower than
1096 * this value or SupplyCurrentLowerTime is 0.
1097 *
1098 * - Minimum Value: 0.0
1099 * - Maximum Value: 500
1100 * - Default Value: 40
1101 * - Units: A
1102 *
1103 * \param newSupplyCurrentLowerLimit Parameter to modify
1104 * \returns Itself
1105 */
1106 constexpr CurrentLimitsConfigs &WithSupplyCurrentLowerLimit(units::current::ampere_t newSupplyCurrentLowerLimit)
1107 {
1108 SupplyCurrentLowerLimit = std::move(newSupplyCurrentLowerLimit);
1109 return *this;
1110 }
1111
1112 /**
1113 * \brief Modifies this configuration's SupplyCurrentLowerTime parameter and returns itself for
1114 * method-chaining and easier to use config API.
1115 *
1116 * Reduces supply current to the SupplyCurrentLowerLimit after
1117 * limiting to SupplyCurrentLimit for this period of time. If this is
1118 * set to 0, SupplyCurrentLowerLimit will be ignored.
1119 *
1120 * - Minimum Value: 0.0
1121 * - Maximum Value: 2.5
1122 * - Default Value: 1.0
1123 * - Units: seconds
1124 *
1125 * \param newSupplyCurrentLowerTime Parameter to modify
1126 * \returns Itself
1127 */
1128 constexpr CurrentLimitsConfigs &WithSupplyCurrentLowerTime(units::time::second_t newSupplyCurrentLowerTime)
1129 {
1130 SupplyCurrentLowerTime = std::move(newSupplyCurrentLowerTime);
1131 return *this;
1132 }
1133
1134
1135
1136 std::string ToString() const override
1137 {
1138 std::stringstream ss;
1139 ss << "Config Group: CurrentLimits" << std::endl;
1140 ss << " StatorCurrentLimit: " << StatorCurrentLimit.to<double>() << " A" << std::endl;
1141 ss << " StatorCurrentLimitEnable: " << StatorCurrentLimitEnable << std::endl;
1142 ss << " SupplyCurrentLimit: " << SupplyCurrentLimit.to<double>() << " A" << std::endl;
1143 ss << " SupplyCurrentLimitEnable: " << SupplyCurrentLimitEnable << std::endl;
1144 ss << " SupplyCurrentLowerLimit: " << SupplyCurrentLowerLimit.to<double>() << " A" << std::endl;
1145 ss << " SupplyCurrentLowerTime: " << SupplyCurrentLowerTime.to<double>() << " seconds" << std::endl;
1146 return ss.str();
1147 }
1148
1149 std::string Serialize() const override
1150 {
1151 std::stringstream ss;
1152 char *ref;
1153 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_StatorCurrentLimit, StatorCurrentLimit.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1154 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_StatorCurrLimitEn, StatorCurrentLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1155 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLimit, SupplyCurrentLimit.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1156 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrLimitEn, SupplyCurrentLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1157 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLowerLimit, SupplyCurrentLowerLimit.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1158 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLowerTime, SupplyCurrentLowerTime.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1159 return ss.str();
1160 }
1161
1162 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
1163 {
1164 const char *string_c_str = to_deserialize.c_str();
1165 size_t string_length = to_deserialize.length();
1166 double StatorCurrentLimitVal = StatorCurrentLimit.to<double>();
1167 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_StatorCurrentLimit, string_c_str, string_length, &StatorCurrentLimitVal);
1168 StatorCurrentLimit = units::current::ampere_t{StatorCurrentLimitVal};
1169 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_StatorCurrLimitEn, string_c_str, string_length, &StatorCurrentLimitEnable);
1170 double SupplyCurrentLimitVal = SupplyCurrentLimit.to<double>();
1171 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLimit, string_c_str, string_length, &SupplyCurrentLimitVal);
1172 SupplyCurrentLimit = units::current::ampere_t{SupplyCurrentLimitVal};
1173 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrLimitEn, string_c_str, string_length, &SupplyCurrentLimitEnable);
1174 double SupplyCurrentLowerLimitVal = SupplyCurrentLowerLimit.to<double>();
1175 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLowerLimit, string_c_str, string_length, &SupplyCurrentLowerLimitVal);
1176 SupplyCurrentLowerLimit = units::current::ampere_t{SupplyCurrentLowerLimitVal};
1177 double SupplyCurrentLowerTimeVal = SupplyCurrentLowerTime.to<double>();
1178 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyCurrentLowerTime, string_c_str, string_length, &SupplyCurrentLowerTimeVal);
1179 SupplyCurrentLowerTime = units::time::second_t{SupplyCurrentLowerTimeVal};
1180 return 0;
1181 }
1182};
1183
1184
1185/**
1186 * \brief Configs that affect Voltage control types.
1187 *
1188 * \details Includes peak output voltages and other configs affecting
1189 * voltage measurements.
1190 */
1192{
1193public:
1194 constexpr VoltageConfigs() = default;
1195
1196 /**
1197 * \brief The time constant (in seconds) of the low-pass filter for
1198 * the supply voltage.
1199 *
1200 * \details This impacts the filtering for the reported supply
1201 * voltage, and any control strategies that use the supply voltage
1202 * (such as voltage control on a motor controller).
1203 *
1204 * - Minimum Value: 0.0
1205 * - Maximum Value: 0.1
1206 * - Default Value: 0
1207 * - Units: seconds
1208 */
1209 units::time::second_t SupplyVoltageTimeConstant = 0_s;
1210 /**
1211 * \brief Maximum (forward) output during voltage based control modes.
1212 *
1213 * - Minimum Value: -16
1214 * - Maximum Value: 16
1215 * - Default Value: 16
1216 * - Units: V
1217 */
1218 units::voltage::volt_t PeakForwardVoltage = 16_V;
1219 /**
1220 * \brief Minimum (reverse) output during voltage based control modes.
1221 *
1222 * - Minimum Value: -16
1223 * - Maximum Value: 16
1224 * - Default Value: -16
1225 * - Units: V
1226 */
1227 units::voltage::volt_t PeakReverseVoltage = -16_V;
1228
1229 /**
1230 * \brief Modifies this configuration's SupplyVoltageTimeConstant parameter and returns itself for
1231 * method-chaining and easier to use config API.
1232 *
1233 * The time constant (in seconds) of the low-pass filter for the
1234 * supply voltage.
1235 *
1236 * \details This impacts the filtering for the reported supply
1237 * voltage, and any control strategies that use the supply voltage
1238 * (such as voltage control on a motor controller).
1239 *
1240 * - Minimum Value: 0.0
1241 * - Maximum Value: 0.1
1242 * - Default Value: 0
1243 * - Units: seconds
1244 *
1245 * \param newSupplyVoltageTimeConstant Parameter to modify
1246 * \returns Itself
1247 */
1248 constexpr VoltageConfigs &WithSupplyVoltageTimeConstant(units::time::second_t newSupplyVoltageTimeConstant)
1249 {
1250 SupplyVoltageTimeConstant = std::move(newSupplyVoltageTimeConstant);
1251 return *this;
1252 }
1253
1254 /**
1255 * \brief Modifies this configuration's PeakForwardVoltage parameter and returns itself for
1256 * method-chaining and easier to use config API.
1257 *
1258 * Maximum (forward) output during voltage based control modes.
1259 *
1260 * - Minimum Value: -16
1261 * - Maximum Value: 16
1262 * - Default Value: 16
1263 * - Units: V
1264 *
1265 * \param newPeakForwardVoltage Parameter to modify
1266 * \returns Itself
1267 */
1268 constexpr VoltageConfigs &WithPeakForwardVoltage(units::voltage::volt_t newPeakForwardVoltage)
1269 {
1270 PeakForwardVoltage = std::move(newPeakForwardVoltage);
1271 return *this;
1272 }
1273
1274 /**
1275 * \brief Modifies this configuration's PeakReverseVoltage parameter and returns itself for
1276 * method-chaining and easier to use config API.
1277 *
1278 * Minimum (reverse) output during voltage based control modes.
1279 *
1280 * - Minimum Value: -16
1281 * - Maximum Value: 16
1282 * - Default Value: -16
1283 * - Units: V
1284 *
1285 * \param newPeakReverseVoltage Parameter to modify
1286 * \returns Itself
1287 */
1288 constexpr VoltageConfigs &WithPeakReverseVoltage(units::voltage::volt_t newPeakReverseVoltage)
1289 {
1290 PeakReverseVoltage = std::move(newPeakReverseVoltage);
1291 return *this;
1292 }
1293
1294
1295
1296 std::string ToString() const override
1297 {
1298 std::stringstream ss;
1299 ss << "Config Group: Voltage" << std::endl;
1300 ss << " SupplyVoltageTimeConstant: " << SupplyVoltageTimeConstant.to<double>() << " seconds" << std::endl;
1301 ss << " PeakForwardVoltage: " << PeakForwardVoltage.to<double>() << " V" << std::endl;
1302 ss << " PeakReverseVoltage: " << PeakReverseVoltage.to<double>() << " V" << std::endl;
1303 return ss.str();
1304 }
1305
1306 std::string Serialize() const override
1307 {
1308 std::stringstream ss;
1309 char *ref;
1310 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyVLowpassTau, SupplyVoltageTimeConstant.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1311 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForwardV, PeakForwardVoltage.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1312 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakReverseV, PeakReverseVoltage.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1313 return ss.str();
1314 }
1315
1316 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
1317 {
1318 const char *string_c_str = to_deserialize.c_str();
1319 size_t string_length = to_deserialize.length();
1320 double SupplyVoltageTimeConstantVal = SupplyVoltageTimeConstant.to<double>();
1321 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SupplyVLowpassTau, string_c_str, string_length, &SupplyVoltageTimeConstantVal);
1322 SupplyVoltageTimeConstant = units::time::second_t{SupplyVoltageTimeConstantVal};
1323 double PeakForwardVoltageVal = PeakForwardVoltage.to<double>();
1324 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForwardV, string_c_str, string_length, &PeakForwardVoltageVal);
1325 PeakForwardVoltage = units::voltage::volt_t{PeakForwardVoltageVal};
1326 double PeakReverseVoltageVal = PeakReverseVoltage.to<double>();
1327 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakReverseV, string_c_str, string_length, &PeakReverseVoltageVal);
1328 PeakReverseVoltage = units::voltage::volt_t{PeakReverseVoltageVal};
1329 return 0;
1330 }
1331};
1332
1333
1334/**
1335 * \brief Configs that affect Torque Current control types.
1336 *
1337 * \details Includes the maximum and minimum applied torque output and
1338 * the neutral deadband used during TorqueCurrentFOC
1339 * requests.
1340 */
1342{
1343public:
1344 constexpr TorqueCurrentConfigs() = default;
1345
1346 /**
1347 * \brief Maximum (forward) output during torque current based control
1348 * modes.
1349 *
1350 * - Minimum Value: -800
1351 * - Maximum Value: 800
1352 * - Default Value: 800
1353 * - Units: A
1354 */
1355 units::current::ampere_t PeakForwardTorqueCurrent = 800_A;
1356 /**
1357 * \brief Minimum (reverse) output during torque current based control
1358 * modes.
1359 *
1360 * - Minimum Value: -800
1361 * - Maximum Value: 800
1362 * - Default Value: -800
1363 * - Units: A
1364 */
1365 units::current::ampere_t PeakReverseTorqueCurrent = -800_A;
1366 /**
1367 * \brief Configures the output deadband during torque current based
1368 * control modes.
1369 *
1370 * - Minimum Value: 0
1371 * - Maximum Value: 25
1372 * - Default Value: 0.0
1373 * - Units: A
1374 */
1375 units::current::ampere_t TorqueNeutralDeadband = 0.0_A;
1376
1377 /**
1378 * \brief Modifies this configuration's PeakForwardTorqueCurrent parameter and returns itself for
1379 * method-chaining and easier to use config API.
1380 *
1381 * Maximum (forward) output during torque current based control modes.
1382 *
1383 * - Minimum Value: -800
1384 * - Maximum Value: 800
1385 * - Default Value: 800
1386 * - Units: A
1387 *
1388 * \param newPeakForwardTorqueCurrent Parameter to modify
1389 * \returns Itself
1390 */
1391 constexpr TorqueCurrentConfigs &WithPeakForwardTorqueCurrent(units::current::ampere_t newPeakForwardTorqueCurrent)
1392 {
1393 PeakForwardTorqueCurrent = std::move(newPeakForwardTorqueCurrent);
1394 return *this;
1395 }
1396
1397 /**
1398 * \brief Modifies this configuration's PeakReverseTorqueCurrent parameter and returns itself for
1399 * method-chaining and easier to use config API.
1400 *
1401 * Minimum (reverse) output during torque current based control modes.
1402 *
1403 * - Minimum Value: -800
1404 * - Maximum Value: 800
1405 * - Default Value: -800
1406 * - Units: A
1407 *
1408 * \param newPeakReverseTorqueCurrent Parameter to modify
1409 * \returns Itself
1410 */
1411 constexpr TorqueCurrentConfigs &WithPeakReverseTorqueCurrent(units::current::ampere_t newPeakReverseTorqueCurrent)
1412 {
1413 PeakReverseTorqueCurrent = std::move(newPeakReverseTorqueCurrent);
1414 return *this;
1415 }
1416
1417 /**
1418 * \brief Modifies this configuration's TorqueNeutralDeadband parameter and returns itself for
1419 * method-chaining and easier to use config API.
1420 *
1421 * Configures the output deadband during torque current based control
1422 * modes.
1423 *
1424 * - Minimum Value: 0
1425 * - Maximum Value: 25
1426 * - Default Value: 0.0
1427 * - Units: A
1428 *
1429 * \param newTorqueNeutralDeadband Parameter to modify
1430 * \returns Itself
1431 */
1432 constexpr TorqueCurrentConfigs &WithTorqueNeutralDeadband(units::current::ampere_t newTorqueNeutralDeadband)
1433 {
1434 TorqueNeutralDeadband = std::move(newTorqueNeutralDeadband);
1435 return *this;
1436 }
1437
1438
1439
1440 std::string ToString() const override
1441 {
1442 std::stringstream ss;
1443 ss << "Config Group: TorqueCurrent" << std::endl;
1444 ss << " PeakForwardTorqueCurrent: " << PeakForwardTorqueCurrent.to<double>() << " A" << std::endl;
1445 ss << " PeakReverseTorqueCurrent: " << PeakReverseTorqueCurrent.to<double>() << " A" << std::endl;
1446 ss << " TorqueNeutralDeadband: " << TorqueNeutralDeadband.to<double>() << " A" << std::endl;
1447 return ss.str();
1448 }
1449
1450 std::string Serialize() const override
1451 {
1452 std::stringstream ss;
1453 char *ref;
1454 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForTorqCurr, PeakForwardTorqueCurrent.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1455 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakRevTorqCurr, PeakReverseTorqueCurrent.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1456 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueNeutralDB, TorqueNeutralDeadband.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1457 return ss.str();
1458 }
1459
1460 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
1461 {
1462 const char *string_c_str = to_deserialize.c_str();
1463 size_t string_length = to_deserialize.length();
1464 double PeakForwardTorqueCurrentVal = PeakForwardTorqueCurrent.to<double>();
1465 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakForTorqCurr, string_c_str, string_length, &PeakForwardTorqueCurrentVal);
1466 PeakForwardTorqueCurrent = units::current::ampere_t{PeakForwardTorqueCurrentVal};
1467 double PeakReverseTorqueCurrentVal = PeakReverseTorqueCurrent.to<double>();
1468 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakRevTorqCurr, string_c_str, string_length, &PeakReverseTorqueCurrentVal);
1469 PeakReverseTorqueCurrent = units::current::ampere_t{PeakReverseTorqueCurrentVal};
1470 double TorqueNeutralDeadbandVal = TorqueNeutralDeadband.to<double>();
1471 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueNeutralDB, string_c_str, string_length, &TorqueNeutralDeadbandVal);
1472 TorqueNeutralDeadband = units::current::ampere_t{TorqueNeutralDeadbandVal};
1473 return 0;
1474 }
1475};
1476
1477
1478/**
1479 * \brief Configs that affect the feedback of this motor controller.
1480 *
1481 * \details Includes feedback sensor source, any offsets for the
1482 * feedback sensor, and various ratios to describe the
1483 * relationship between the sensor and the mechanism for
1484 * closed looping.
1485 */
1487{
1488public:
1489 constexpr FeedbackConfigs() = default;
1490
1491 /**
1492 * \brief The offset applied to the absolute integrated rotor sensor.
1493 * This can be used to zero the rotor in applications that are within
1494 * one rotor rotation.
1495 *
1496 * - Minimum Value: -1
1497 * - Maximum Value: 1
1498 * - Default Value: 0.0
1499 * - Units: rotations
1500 */
1501 units::angle::turn_t FeedbackRotorOffset = 0.0_tr;
1502 /**
1503 * \brief The ratio of sensor rotations to the mechanism's output,
1504 * where a ratio greater than 1 is a reduction.
1505 *
1506 * This is equivalent to the mechanism's gear ratio if the sensor is
1507 * located on the input of a gearbox. If sensor is on the output of a
1508 * gearbox, then this is typically set to 1.
1509 *
1510 * We recommend against using this config to perform onboard unit
1511 * conversions. Instead, unit conversions should be performed in
1512 * robot code using the units library.
1513 *
1514 * If this is set to zero, the device will reset back to one.
1515 *
1516 * - Minimum Value: -1000
1517 * - Maximum Value: 1000
1518 * - Default Value: 1.0
1519 * - Units: scalar
1520 */
1521 units::dimensionless::scalar_t SensorToMechanismRatio = 1.0;
1522 /**
1523 * \brief The ratio of motor rotor rotations to remote sensor
1524 * rotations, where a ratio greater than 1 is a reduction.
1525 *
1526 * The Talon FX is capable of fusing a remote CANcoder with its rotor
1527 * sensor to produce a high-bandwidth sensor source. This feature
1528 * requires specifying the ratio between the motor rotor and the
1529 * remote sensor.
1530 *
1531 * If this is set to zero, the device will reset back to one.
1532 *
1533 * - Minimum Value: -1000
1534 * - Maximum Value: 1000
1535 * - Default Value: 1.0
1536 * - Units: scalar
1537 */
1538 units::dimensionless::scalar_t RotorToSensorRatio = 1.0;
1539 /**
1540 * \brief Choose what sensor source is reported via API and used by
1541 * closed-loop and limit features. The default is RotorSensor, which
1542 * uses the internal rotor sensor in the Talon.
1543 *
1544 * Choose Remote* to use another sensor on the same CAN bus (this also
1545 * requires setting FeedbackRemoteSensorID). Talon will update its
1546 * position and velocity whenever the remote sensor publishes its
1547 * information on CAN bus, and the Talon internal rotor will not be
1548 * used.
1549 *
1550 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
1551 * sensor's information with the internal rotor, which provides the
1552 * best possible position and velocity for accuracy and bandwidth
1553 * (this also requires setting FeedbackRemoteSensorID). This was
1554 * developed for applications such as swerve-azimuth.
1555 *
1556 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
1557 * internal rotor position against another sensor, then continue to
1558 * use the rotor sensor for closed loop control (this also requires
1559 * setting FeedbackRemoteSensorID). The Talon will report if its
1560 * internal position differs significantly from the reported remote
1561 * sensor position. This was developed for mechanisms where there is
1562 * a risk of the sensor failing in such a way that it reports a
1563 * position that does not match the mechanism, such as the sensor
1564 * mounting assembly breaking off.
1565 *
1566 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
1567 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
1568 * also requires setting FeedbackRemoteSensorID). Talon will update
1569 * its position to match the selected value whenever Pigeon2 publishes
1570 * its information on CAN bus. Note that the Talon position will be in
1571 * rotations and not degrees.
1572 *
1573 * \details Note: When the feedback source is changed to Fused* or
1574 * Sync*, the Talon needs a period of time to fuse before sensor-based
1575 * (soft-limit, closed loop, etc.) features are used. This period of
1576 * time is determined by the update frequency of the remote sensor's
1577 * Position signal.
1578 *
1579 */
1581 /**
1582 * \brief Device ID of which remote device to use. This is not used
1583 * if the Sensor Source is the internal rotor sensor.
1584 *
1585 * - Minimum Value: 0
1586 * - Maximum Value: 62
1587 * - Default Value: 0
1588 * - Units:
1589 */
1591 /**
1592 * \brief The configurable time constant of the Kalman velocity
1593 * filter. The velocity Kalman filter will adjust to act as a low-pass
1594 * with this value as its time constant.
1595 *
1596 * \details If the user is aiming for an expected cutoff frequency,
1597 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
1598 * time constant.
1599 *
1600 * - Minimum Value: 0
1601 * - Maximum Value: 1
1602 * - Default Value: 0
1603 * - Units: seconds
1604 */
1605 units::time::second_t VelocityFilterTimeConstant = 0_s;
1606
1607 /**
1608 * \brief Modifies this configuration's FeedbackRotorOffset parameter and returns itself for
1609 * method-chaining and easier to use config API.
1610 *
1611 * The offset applied to the absolute integrated rotor sensor. This
1612 * can be used to zero the rotor in applications that are within one
1613 * rotor rotation.
1614 *
1615 * - Minimum Value: -1
1616 * - Maximum Value: 1
1617 * - Default Value: 0.0
1618 * - Units: rotations
1619 *
1620 * \param newFeedbackRotorOffset Parameter to modify
1621 * \returns Itself
1622 */
1623 constexpr FeedbackConfigs &WithFeedbackRotorOffset(units::angle::turn_t newFeedbackRotorOffset)
1624 {
1625 FeedbackRotorOffset = std::move(newFeedbackRotorOffset);
1626 return *this;
1627 }
1628
1629 /**
1630 * \brief Modifies this configuration's SensorToMechanismRatio parameter and returns itself for
1631 * method-chaining and easier to use config API.
1632 *
1633 * The ratio of sensor rotations to the mechanism's output, where a
1634 * ratio greater than 1 is a reduction.
1635 *
1636 * This is equivalent to the mechanism's gear ratio if the sensor is
1637 * located on the input of a gearbox. If sensor is on the output of a
1638 * gearbox, then this is typically set to 1.
1639 *
1640 * We recommend against using this config to perform onboard unit
1641 * conversions. Instead, unit conversions should be performed in
1642 * robot code using the units library.
1643 *
1644 * If this is set to zero, the device will reset back to one.
1645 *
1646 * - Minimum Value: -1000
1647 * - Maximum Value: 1000
1648 * - Default Value: 1.0
1649 * - Units: scalar
1650 *
1651 * \param newSensorToMechanismRatio Parameter to modify
1652 * \returns Itself
1653 */
1654 constexpr FeedbackConfigs &WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
1655 {
1656 SensorToMechanismRatio = std::move(newSensorToMechanismRatio);
1657 return *this;
1658 }
1659
1660 /**
1661 * \brief Modifies this configuration's RotorToSensorRatio parameter and returns itself for
1662 * method-chaining and easier to use config API.
1663 *
1664 * The ratio of motor rotor rotations to remote sensor rotations,
1665 * where a ratio greater than 1 is a reduction.
1666 *
1667 * The Talon FX is capable of fusing a remote CANcoder with its rotor
1668 * sensor to produce a high-bandwidth sensor source. This feature
1669 * requires specifying the ratio between the motor rotor and the
1670 * remote sensor.
1671 *
1672 * If this is set to zero, the device will reset back to one.
1673 *
1674 * - Minimum Value: -1000
1675 * - Maximum Value: 1000
1676 * - Default Value: 1.0
1677 * - Units: scalar
1678 *
1679 * \param newRotorToSensorRatio Parameter to modify
1680 * \returns Itself
1681 */
1682 constexpr FeedbackConfigs &WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
1683 {
1684 RotorToSensorRatio = std::move(newRotorToSensorRatio);
1685 return *this;
1686 }
1687
1688 /**
1689 * \brief Modifies this configuration's FeedbackSensorSource parameter and returns itself for
1690 * method-chaining and easier to use config API.
1691 *
1692 * Choose what sensor source is reported via API and used by
1693 * closed-loop and limit features. The default is RotorSensor, which
1694 * uses the internal rotor sensor in the Talon.
1695 *
1696 * Choose Remote* to use another sensor on the same CAN bus (this also
1697 * requires setting FeedbackRemoteSensorID). Talon will update its
1698 * position and velocity whenever the remote sensor publishes its
1699 * information on CAN bus, and the Talon internal rotor will not be
1700 * used.
1701 *
1702 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
1703 * sensor's information with the internal rotor, which provides the
1704 * best possible position and velocity for accuracy and bandwidth
1705 * (this also requires setting FeedbackRemoteSensorID). This was
1706 * developed for applications such as swerve-azimuth.
1707 *
1708 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
1709 * internal rotor position against another sensor, then continue to
1710 * use the rotor sensor for closed loop control (this also requires
1711 * setting FeedbackRemoteSensorID). The Talon will report if its
1712 * internal position differs significantly from the reported remote
1713 * sensor position. This was developed for mechanisms where there is
1714 * a risk of the sensor failing in such a way that it reports a
1715 * position that does not match the mechanism, such as the sensor
1716 * mounting assembly breaking off.
1717 *
1718 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
1719 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
1720 * also requires setting FeedbackRemoteSensorID). Talon will update
1721 * its position to match the selected value whenever Pigeon2 publishes
1722 * its information on CAN bus. Note that the Talon position will be in
1723 * rotations and not degrees.
1724 *
1725 * \details Note: When the feedback source is changed to Fused* or
1726 * Sync*, the Talon needs a period of time to fuse before sensor-based
1727 * (soft-limit, closed loop, etc.) features are used. This period of
1728 * time is determined by the update frequency of the remote sensor's
1729 * Position signal.
1730 *
1731 *
1732 * \param newFeedbackSensorSource Parameter to modify
1733 * \returns Itself
1734 */
1736 {
1737 FeedbackSensorSource = std::move(newFeedbackSensorSource);
1738 return *this;
1739 }
1740
1741 /**
1742 * \brief Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for
1743 * method-chaining and easier to use config API.
1744 *
1745 * Device ID of which remote device to use. This is not used if the
1746 * Sensor Source is the internal rotor sensor.
1747 *
1748 * - Minimum Value: 0
1749 * - Maximum Value: 62
1750 * - Default Value: 0
1751 * - Units:
1752 *
1753 * \param newFeedbackRemoteSensorID Parameter to modify
1754 * \returns Itself
1755 */
1756 constexpr FeedbackConfigs &WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
1757 {
1758 FeedbackRemoteSensorID = std::move(newFeedbackRemoteSensorID);
1759 return *this;
1760 }
1761
1762 /**
1763 * \brief Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for
1764 * method-chaining and easier to use config API.
1765 *
1766 * The configurable time constant of the Kalman velocity filter. The
1767 * velocity Kalman filter will adjust to act as a low-pass with this
1768 * value as its time constant.
1769 *
1770 * \details If the user is aiming for an expected cutoff frequency,
1771 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
1772 * time constant.
1773 *
1774 * - Minimum Value: 0
1775 * - Maximum Value: 1
1776 * - Default Value: 0
1777 * - Units: seconds
1778 *
1779 * \param newVelocityFilterTimeConstant Parameter to modify
1780 * \returns Itself
1781 */
1782 constexpr FeedbackConfigs &WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
1783 {
1784 VelocityFilterTimeConstant = std::move(newVelocityFilterTimeConstant);
1785 return *this;
1786 }
1787
1788 /**
1789 * \brief Helper method to configure this feedback group to use
1790 * RemoteCANcoder by passing in the CANcoder object.
1791 *
1792 * When using RemoteCANcoder, the Talon will use another
1793 * CANcoder on the same CAN bus. The Talon will update its
1794 * position and velocity whenever CANcoder publishes its
1795 * information on CAN bus, and the Talon internal rotor will
1796 * not be used.
1797 *
1798 * \param device CANcoder reference to use for RemoteCANcoder
1799 * \returns Itself
1800 */
1802
1803 /**
1804 * \brief Helper method to configure this feedback group to use
1805 * FusedCANcoder by passing in the CANcoder object.
1806 *
1807 * When using FusedCANcoder (requires Phoenix Pro), the Talon
1808 * will fuse another CANcoder's information with the internal
1809 * rotor, which provides the best possible position and
1810 * velocity for accuracy and bandwidth. FusedCANcoder was
1811 * developed for applications such as swerve-azimuth.
1812 *
1813 * \param device CANcoder reference to use for FusedCANcoder
1814 * \returns Itself
1815 */
1817
1818 /**
1819 * \brief Helper method to configure this feedback group to use
1820 * SyncCANcoder by passing in the CANcoder object.
1821 *
1822 * When using SyncCANcoder (requires Phoenix Pro), the Talon
1823 * will synchronize its internal rotor position against another
1824 * CANcoder, then continue to use the rotor sensor for closed
1825 * loop control. The Talon will report if its internal position
1826 * differs significantly from the reported CANcoder position.
1827 * SyncCANcoder was developed for mechanisms where there is a
1828 * risk of the CANcoder failing in such a way that it reports a
1829 * position that does not match the mechanism, such as the
1830 * sensor mounting assembly breaking off.
1831 *
1832 * \param device CANcoder reference to use for SyncCANcoder
1833 * \returns Itself
1834 */
1836
1837 /**
1838 * \brief Helper method to configure this feedback group to use
1839 * RemoteCANdi PWM 1 by passing in the CANdi object.
1840 *
1841 * \param device CANdi reference to use for RemoteCANdi
1842 * \returns Itself
1843 */
1845
1846 /**
1847 * \brief Helper method to configure this feedback group to use
1848 * RemoteCANdi PWM 2 by passing in the CANdi object.
1849 *
1850 * \param device CANdi reference to use for RemoteCANdi
1851 * \returns Itself
1852 */
1854
1855 /**
1856 * \brief Helper method to configure this feedback group to use
1857 * RemoteCANdi Quadrature by passing in the CANdi object.
1858 *
1859 * \param device CANdi reference to use for RemoteCANdi
1860 * \returns Itself
1861 */
1863
1864 /**
1865 * \brief Helper method to configure this feedback group to use
1866 * FusedCANdi PWM 1 by passing in the CANdi object.
1867 *
1868 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1869 * fuse another CANdi™ branded device's information with the
1870 * internal rotor, which provides the best possible position
1871 * and velocity for accuracy and bandwidth.
1872 *
1873 * \param device CANdi reference to use for FusedCANdi
1874 * \returns Itself
1875 */
1877
1878 /**
1879 * \brief Helper method to configure this feedback group to use
1880 * FusedCANdi PWM 2 by passing in the CANdi object.
1881 *
1882 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1883 * fuse another CANdi™ branded device's information with the
1884 * internal rotor, which provides the best possible position
1885 * and velocity for accuracy and bandwidth.
1886 *
1887 * \param device CANdi reference to use for FusedCANdi
1888 * \returns Itself
1889 */
1891
1892 /**
1893 * \brief Helper method to configure this feedback group to use
1894 * FusedCANdi Quadrature by passing in the CANdi object.
1895 *
1896 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1897 * fuse another CANdi™ branded device's information with the
1898 * internal rotor, which provides the best possible position
1899 * and velocity for accuracy and bandwidth.
1900 *
1901 * \param device CANdi reference to use for FusedCANdi
1902 * \returns Itself
1903 */
1905
1906 /**
1907 * \brief Helper method to configure this feedback group to use
1908 * SyncCANdi PWM 1 by passing in the CANdi object.
1909 *
1910 * When using SyncCANdi (requires Phoenix Pro), the Talon will
1911 * synchronize its internal rotor position against another
1912 * CANdi™ branded device, then continue to use the rotor sensor
1913 * for closed loop control. The Talon will report if its
1914 * internal position differs significantly from the reported
1915 * CANdi™ branded device's position. SyncCANdi was developed
1916 * for mechanisms where there is a risk of the CANdi™ branded
1917 * device failing in such a way that it reports a position that
1918 * does not match the mechanism, such as the sensor mounting
1919 * assembly breaking off.
1920 *
1921 * \param device CANdi reference to use for SyncCANdi
1922 * \returns Itself
1923 */
1925
1926 /**
1927 * \brief Helper method to configure this feedback group to use
1928 * SyncCANdi PWM 2 by passing in the CANdi object.
1929 *
1930 * When using SyncCANdi (requires Phoenix Pro), the Talon will
1931 * synchronize its internal rotor position against another
1932 * CANdi™ branded device, then continue to use the rotor sensor
1933 * for closed loop control. The Talon will report if its
1934 * internal position differs significantly from the reported
1935 * CANdi™ branded device's position. SyncCANdi was developed
1936 * for mechanisms where there is a risk of the CANdi™ branded
1937 * device failing in such a way that it reports a position that
1938 * does not match the mechanism, such as the sensor mounting
1939 * assembly breaking off.
1940 *
1941 * \param device CANdi reference to use for SyncCANdi
1942 * \returns Itself
1943 */
1945
1946
1947
1948 std::string ToString() const override
1949 {
1950 std::stringstream ss;
1951 ss << "Config Group: Feedback" << std::endl;
1952 ss << " FeedbackRotorOffset: " << FeedbackRotorOffset.to<double>() << " rotations" << std::endl;
1953 ss << " SensorToMechanismRatio: " << SensorToMechanismRatio.to<double>() << " scalar" << std::endl;
1954 ss << " RotorToSensorRatio: " << RotorToSensorRatio.to<double>() << " scalar" << std::endl;
1955 ss << " FeedbackSensorSource: " << FeedbackSensorSource << std::endl;
1956 ss << " FeedbackRemoteSensorID: " << FeedbackRemoteSensorID << std::endl;
1957 ss << " VelocityFilterTimeConstant: " << VelocityFilterTimeConstant.to<double>() << " seconds" << std::endl;
1958 return ss.str();
1959 }
1960
1961 std::string Serialize() const override
1962 {
1963 std::stringstream ss;
1964 char *ref;
1965 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_FeedbackRotorOffset, FeedbackRotorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1966 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, SensorToMechanismRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1967 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, RotorToSensorRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1968 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackSensorSource, FeedbackSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1969 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, FeedbackRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1970 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, VelocityFilterTimeConstant.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1971 return ss.str();
1972 }
1973
1974 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
1975 {
1976 const char *string_c_str = to_deserialize.c_str();
1977 size_t string_length = to_deserialize.length();
1978 double FeedbackRotorOffsetVal = FeedbackRotorOffset.to<double>();
1979 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_FeedbackRotorOffset, string_c_str, string_length, &FeedbackRotorOffsetVal);
1980 FeedbackRotorOffset = units::angle::turn_t{FeedbackRotorOffsetVal};
1981 double SensorToMechanismRatioVal = SensorToMechanismRatio.to<double>();
1982 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, string_c_str, string_length, &SensorToMechanismRatioVal);
1983 SensorToMechanismRatio = units::dimensionless::scalar_t{SensorToMechanismRatioVal};
1984 double RotorToSensorRatioVal = RotorToSensorRatio.to<double>();
1985 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, string_c_str, string_length, &RotorToSensorRatioVal);
1986 RotorToSensorRatio = units::dimensionless::scalar_t{RotorToSensorRatioVal};
1987 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackSensorSource, string_c_str, string_length, &FeedbackSensorSource.value);
1988 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, string_c_str, string_length, &FeedbackRemoteSensorID);
1989 double VelocityFilterTimeConstantVal = VelocityFilterTimeConstant.to<double>();
1990 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, string_c_str, string_length, &VelocityFilterTimeConstantVal);
1991 VelocityFilterTimeConstant = units::time::second_t{VelocityFilterTimeConstantVal};
1992 return 0;
1993 }
1994};
1995
1996
1997/**
1998 * \brief Configs that affect the external feedback sensor of this
1999 * motor controller.
2000 *
2001 * \details Includes feedback sensor source, offsets and sensor phase
2002 * for the feedback sensor, and various ratios to describe
2003 * the relationship between the sensor and the mechanism for
2004 * closed looping.
2005 */
2007{
2008public:
2009 constexpr ExternalFeedbackConfigs() = default;
2010
2011 /**
2012 * \brief The ratio of sensor rotations to the mechanism's output,
2013 * where a ratio greater than 1 is a reduction.
2014 *
2015 * This is equivalent to the mechanism's gear ratio if the sensor is
2016 * located on the input of a gearbox. If sensor is on the output of a
2017 * gearbox, then this is typically set to 1.
2018 *
2019 * We recommend against using this config to perform onboard unit
2020 * conversions. Instead, unit conversions should be performed in
2021 * robot code using the units library.
2022 *
2023 * If this is set to zero, the device will reset back to one.
2024 *
2025 * - Minimum Value: -1000
2026 * - Maximum Value: 1000
2027 * - Default Value: 1.0
2028 * - Units: scalar
2029 */
2030 units::dimensionless::scalar_t SensorToMechanismRatio = 1.0;
2031 /**
2032 * \brief The ratio of motor rotor rotations to remote sensor
2033 * rotations, where a ratio greater than 1 is a reduction.
2034 *
2035 * The Talon FX is capable of fusing a remote CANcoder with its rotor
2036 * sensor to produce a high-bandwidth sensor source. This feature
2037 * requires specifying the ratio between the motor rotor and the
2038 * remote sensor.
2039 *
2040 * If this is set to zero, the device will reset back to one.
2041 *
2042 * - Minimum Value: -1000
2043 * - Maximum Value: 1000
2044 * - Default Value: 1.0
2045 * - Units: scalar
2046 */
2047 units::dimensionless::scalar_t RotorToSensorRatio = 1.0;
2048 /**
2049 * \brief Device ID of which remote device to use. This is not used
2050 * if the Sensor Source is the internal rotor sensor.
2051 *
2052 * - Minimum Value: 0
2053 * - Maximum Value: 62
2054 * - Default Value: 0
2055 * - Units:
2056 */
2058 /**
2059 * \brief The configurable time constant of the Kalman velocity
2060 * filter. The velocity Kalman filter will adjust to act as a low-pass
2061 * with this value as its time constant.
2062 *
2063 * \details If the user is aiming for an expected cutoff frequency,
2064 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
2065 * time constant.
2066 *
2067 * - Minimum Value: 0
2068 * - Maximum Value: 1
2069 * - Default Value: 0
2070 * - Units: seconds
2071 */
2072 units::time::second_t VelocityFilterTimeConstant = 0_s;
2073 /**
2074 * \brief The offset applied to any absolute sensor connected to the
2075 * Talon data port. This is only supported when using the PulseWidth
2076 * sensor source.
2077 *
2078 * This can be used to zero the sensor position in applications where
2079 * the sensor is 1:1 with the mechanism.
2080 *
2081 * - Minimum Value: -1
2082 * - Maximum Value: 1
2083 * - Default Value: 0.0
2084 * - Units: rotations
2085 */
2086 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
2087 /**
2088 * \brief Choose what sensor source is reported via API and used by
2089 * closed-loop and limit features. The default is Commutation, which
2090 * uses the external sensor used for motor commutation.
2091 *
2092 * Choose Remote* to use another sensor on the same CAN bus (this also
2093 * requires setting FeedbackRemoteSensorID). Talon will update its
2094 * position and velocity whenever the remote sensor publishes its
2095 * information on CAN bus, and the Talon commutation sensor will not
2096 * be used.
2097 *
2098 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
2099 * sensor's information with the commutation sensor, which provides
2100 * the best possible position and velocity for accuracy and bandwidth
2101 * (this also requires setting FeedbackRemoteSensorID). This was
2102 * developed for applications such as swerve-azimuth.
2103 *
2104 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
2105 * commutation sensor position against another sensor, then continue
2106 * to use the rotor sensor for closed loop control (this also requires
2107 * setting FeedbackRemoteSensorID). The Talon will report if its
2108 * internal position differs significantly from the reported remote
2109 * sensor position. This was developed for mechanisms where there is
2110 * a risk of the sensor failing in such a way that it reports a
2111 * position that does not match the mechanism, such as the sensor
2112 * mounting assembly breaking off.
2113 *
2114 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2115 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2116 * also requires setting FeedbackRemoteSensorID). Talon will update
2117 * its position to match the selected value whenever Pigeon2 publishes
2118 * its information on CAN bus. Note that the Talon position will be in
2119 * rotations and not degrees.
2120 *
2121 * Choose Quadrature to use a quadrature encoder directly attached to
2122 * the Talon data port. This provides velocity and relative position
2123 * measurements.
2124 *
2125 * Choose PulseWidth to use a pulse-width encoder directly attached to
2126 * the Talon data port. This provides velocity and absolute position
2127 * measurements.
2128 *
2129 * \details Note: When the feedback source is changed to Fused* or
2130 * Sync*, the Talon needs a period of time to fuse before sensor-based
2131 * (soft-limit, closed loop, etc.) features are used. This period of
2132 * time is determined by the update frequency of the remote sensor's
2133 * Position signal.
2134 *
2135 */
2137 /**
2138 * \brief The relationship between the motor controlled by a Talon and
2139 * the external sensor connected to the data port. This does not
2140 * affect the commutation sensor or remote sensors.
2141 *
2142 * To determine the sensor phase, set this config to Aligned and drive
2143 * the motor with positive output. If the reported sensor velocity is
2144 * positive, then the phase is Aligned. If the reported sensor
2145 * velocity is negative, then the phase is Opposed.
2146 *
2147 * The sensor direction is automatically inverted along with motor
2148 * invert, so the sensor phase does not need to be changed when motor
2149 * invert changes.
2150 *
2151 */
2153 /**
2154 * \brief The number of quadrature edges in one rotation for the
2155 * quadrature sensor connected to the Talon data port.
2156 *
2157 * This is the total number of transitions from high-to-low or
2158 * low-to-high across both channels per rotation of the sensor. This
2159 * is also equivalent to the Counts Per Revolution when using 4x
2160 * decoding.
2161 *
2162 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
2163 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
2164 * 4096 edges per rotation.
2165 *
2166 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
2167 * RPM.
2168 *
2169 * - Minimum Value: 1
2170 * - Maximum Value: 1000000
2171 * - Default Value: 4096
2172 * - Units:
2173 */
2175 /**
2176 * \brief The positive discontinuity point of the absolute sensor in
2177 * rotations. This determines the point at which the absolute sensor
2178 * wraps around, keeping the absolute position in the range [x-1, x).
2179 *
2180 * - Setting this to 1 makes the absolute position unsigned [0, 1)
2181 * - Setting this to 0.5 makes the absolute position signed [-0.5,
2182 * 0.5)
2183 * - Setting this to 0 makes the absolute position always negative
2184 * [-1, 0)
2185 *
2186 * Many rotational mechanisms such as arms have a region of motion
2187 * that is unreachable. This should be set to the center of that
2188 * region of motion, in non-negative rotations. This affects the
2189 * position of the device at bootup.
2190 *
2191 * \details For example, consider an arm which can travel from -0.2 to
2192 * 0.6 rotations with a little leeway, where 0 is horizontally
2193 * forward. Since -0.2 rotations has the same absolute position as 0.8
2194 * rotations, we can say that the arm typically does not travel in the
2195 * range (0.6, 0.8) rotations. As a result, the discontinuity point
2196 * would be the center of that range, which is 0.7 rotations. This
2197 * results in an absolute sensor range of [-0.3, 0.7) rotations.
2198 *
2199 * On a Talon motor controller, this is only supported when using the
2200 * PulseWidth sensor source.
2201 *
2202 * - Minimum Value: 0.0
2203 * - Maximum Value: 1.0
2204 * - Default Value: 0.5
2205 * - Units: rotations
2206 */
2207 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
2208
2209 /**
2210 * \brief Modifies this configuration's SensorToMechanismRatio parameter and returns itself for
2211 * method-chaining and easier to use config API.
2212 *
2213 * The ratio of sensor rotations to the mechanism's output, where a
2214 * ratio greater than 1 is a reduction.
2215 *
2216 * This is equivalent to the mechanism's gear ratio if the sensor is
2217 * located on the input of a gearbox. If sensor is on the output of a
2218 * gearbox, then this is typically set to 1.
2219 *
2220 * We recommend against using this config to perform onboard unit
2221 * conversions. Instead, unit conversions should be performed in
2222 * robot code using the units library.
2223 *
2224 * If this is set to zero, the device will reset back to one.
2225 *
2226 * - Minimum Value: -1000
2227 * - Maximum Value: 1000
2228 * - Default Value: 1.0
2229 * - Units: scalar
2230 *
2231 * \param newSensorToMechanismRatio Parameter to modify
2232 * \returns Itself
2233 */
2234 constexpr ExternalFeedbackConfigs &WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
2235 {
2236 SensorToMechanismRatio = std::move(newSensorToMechanismRatio);
2237 return *this;
2238 }
2239
2240 /**
2241 * \brief Modifies this configuration's RotorToSensorRatio parameter and returns itself for
2242 * method-chaining and easier to use config API.
2243 *
2244 * The ratio of motor rotor rotations to remote sensor rotations,
2245 * where a ratio greater than 1 is a reduction.
2246 *
2247 * The Talon FX is capable of fusing a remote CANcoder with its rotor
2248 * sensor to produce a high-bandwidth sensor source. This feature
2249 * requires specifying the ratio between the motor rotor and the
2250 * remote sensor.
2251 *
2252 * If this is set to zero, the device will reset back to one.
2253 *
2254 * - Minimum Value: -1000
2255 * - Maximum Value: 1000
2256 * - Default Value: 1.0
2257 * - Units: scalar
2258 *
2259 * \param newRotorToSensorRatio Parameter to modify
2260 * \returns Itself
2261 */
2262 constexpr ExternalFeedbackConfigs &WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
2263 {
2264 RotorToSensorRatio = std::move(newRotorToSensorRatio);
2265 return *this;
2266 }
2267
2268 /**
2269 * \brief Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for
2270 * method-chaining and easier to use config API.
2271 *
2272 * Device ID of which remote device to use. This is not used if the
2273 * Sensor Source is the internal rotor sensor.
2274 *
2275 * - Minimum Value: 0
2276 * - Maximum Value: 62
2277 * - Default Value: 0
2278 * - Units:
2279 *
2280 * \param newFeedbackRemoteSensorID Parameter to modify
2281 * \returns Itself
2282 */
2283 constexpr ExternalFeedbackConfigs &WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
2284 {
2285 FeedbackRemoteSensorID = std::move(newFeedbackRemoteSensorID);
2286 return *this;
2287 }
2288
2289 /**
2290 * \brief Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for
2291 * method-chaining and easier to use config API.
2292 *
2293 * The configurable time constant of the Kalman velocity filter. The
2294 * velocity Kalman filter will adjust to act as a low-pass with this
2295 * value as its time constant.
2296 *
2297 * \details If the user is aiming for an expected cutoff frequency,
2298 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
2299 * time constant.
2300 *
2301 * - Minimum Value: 0
2302 * - Maximum Value: 1
2303 * - Default Value: 0
2304 * - Units: seconds
2305 *
2306 * \param newVelocityFilterTimeConstant Parameter to modify
2307 * \returns Itself
2308 */
2309 constexpr ExternalFeedbackConfigs &WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
2310 {
2311 VelocityFilterTimeConstant = std::move(newVelocityFilterTimeConstant);
2312 return *this;
2313 }
2314
2315 /**
2316 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
2317 * method-chaining and easier to use config API.
2318 *
2319 * The offset applied to any absolute sensor connected to the Talon
2320 * data port. This is only supported when using the PulseWidth sensor
2321 * source.
2322 *
2323 * This can be used to zero the sensor position in applications where
2324 * the sensor is 1:1 with the mechanism.
2325 *
2326 * - Minimum Value: -1
2327 * - Maximum Value: 1
2328 * - Default Value: 0.0
2329 * - Units: rotations
2330 *
2331 * \param newAbsoluteSensorOffset Parameter to modify
2332 * \returns Itself
2333 */
2334 constexpr ExternalFeedbackConfigs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
2335 {
2336 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
2337 return *this;
2338 }
2339
2340 /**
2341 * \brief Modifies this configuration's ExternalFeedbackSensorSource parameter and returns itself for
2342 * method-chaining and easier to use config API.
2343 *
2344 * Choose what sensor source is reported via API and used by
2345 * closed-loop and limit features. The default is Commutation, which
2346 * uses the external sensor used for motor commutation.
2347 *
2348 * Choose Remote* to use another sensor on the same CAN bus (this also
2349 * requires setting FeedbackRemoteSensorID). Talon will update its
2350 * position and velocity whenever the remote sensor publishes its
2351 * information on CAN bus, and the Talon commutation sensor will not
2352 * be used.
2353 *
2354 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
2355 * sensor's information with the commutation sensor, which provides
2356 * the best possible position and velocity for accuracy and bandwidth
2357 * (this also requires setting FeedbackRemoteSensorID). This was
2358 * developed for applications such as swerve-azimuth.
2359 *
2360 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
2361 * commutation sensor position against another sensor, then continue
2362 * to use the rotor sensor for closed loop control (this also requires
2363 * setting FeedbackRemoteSensorID). The Talon will report if its
2364 * internal position differs significantly from the reported remote
2365 * sensor position. This was developed for mechanisms where there is
2366 * a risk of the sensor failing in such a way that it reports a
2367 * position that does not match the mechanism, such as the sensor
2368 * mounting assembly breaking off.
2369 *
2370 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2371 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2372 * also requires setting FeedbackRemoteSensorID). Talon will update
2373 * its position to match the selected value whenever Pigeon2 publishes
2374 * its information on CAN bus. Note that the Talon position will be in
2375 * rotations and not degrees.
2376 *
2377 * Choose Quadrature to use a quadrature encoder directly attached to
2378 * the Talon data port. This provides velocity and relative position
2379 * measurements.
2380 *
2381 * Choose PulseWidth to use a pulse-width encoder directly attached to
2382 * the Talon data port. This provides velocity and absolute position
2383 * measurements.
2384 *
2385 * \details Note: When the feedback source is changed to Fused* or
2386 * Sync*, the Talon needs a period of time to fuse before sensor-based
2387 * (soft-limit, closed loop, etc.) features are used. This period of
2388 * time is determined by the update frequency of the remote sensor's
2389 * Position signal.
2390 *
2391 *
2392 * \param newExternalFeedbackSensorSource Parameter to modify
2393 * \returns Itself
2394 */
2396 {
2397 ExternalFeedbackSensorSource = std::move(newExternalFeedbackSensorSource);
2398 return *this;
2399 }
2400
2401 /**
2402 * \brief Modifies this configuration's SensorPhase parameter and returns itself for
2403 * method-chaining and easier to use config API.
2404 *
2405 * The relationship between the motor controlled by a Talon and the
2406 * external sensor connected to the data port. This does not affect
2407 * the commutation sensor or remote sensors.
2408 *
2409 * To determine the sensor phase, set this config to Aligned and drive
2410 * the motor with positive output. If the reported sensor velocity is
2411 * positive, then the phase is Aligned. If the reported sensor
2412 * velocity is negative, then the phase is Opposed.
2413 *
2414 * The sensor direction is automatically inverted along with motor
2415 * invert, so the sensor phase does not need to be changed when motor
2416 * invert changes.
2417 *
2418 *
2419 * \param newSensorPhase Parameter to modify
2420 * \returns Itself
2421 */
2423 {
2424 SensorPhase = std::move(newSensorPhase);
2425 return *this;
2426 }
2427
2428 /**
2429 * \brief Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for
2430 * method-chaining and easier to use config API.
2431 *
2432 * The number of quadrature edges in one rotation for the quadrature
2433 * sensor connected to the Talon data port.
2434 *
2435 * This is the total number of transitions from high-to-low or
2436 * low-to-high across both channels per rotation of the sensor. This
2437 * is also equivalent to the Counts Per Revolution when using 4x
2438 * decoding.
2439 *
2440 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
2441 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
2442 * 4096 edges per rotation.
2443 *
2444 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
2445 * RPM.
2446 *
2447 * - Minimum Value: 1
2448 * - Maximum Value: 1000000
2449 * - Default Value: 4096
2450 * - Units:
2451 *
2452 * \param newQuadratureEdgesPerRotation Parameter to modify
2453 * \returns Itself
2454 */
2455 constexpr ExternalFeedbackConfigs &WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
2456 {
2457 QuadratureEdgesPerRotation = std::move(newQuadratureEdgesPerRotation);
2458 return *this;
2459 }
2460
2461 /**
2462 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
2463 * method-chaining and easier to use config API.
2464 *
2465 * The positive discontinuity point of the absolute sensor in
2466 * rotations. This determines the point at which the absolute sensor
2467 * wraps around, keeping the absolute position in the range [x-1, x).
2468 *
2469 * - Setting this to 1 makes the absolute position unsigned [0, 1)
2470 * - Setting this to 0.5 makes the absolute position signed [-0.5,
2471 * 0.5)
2472 * - Setting this to 0 makes the absolute position always negative
2473 * [-1, 0)
2474 *
2475 * Many rotational mechanisms such as arms have a region of motion
2476 * that is unreachable. This should be set to the center of that
2477 * region of motion, in non-negative rotations. This affects the
2478 * position of the device at bootup.
2479 *
2480 * \details For example, consider an arm which can travel from -0.2 to
2481 * 0.6 rotations with a little leeway, where 0 is horizontally
2482 * forward. Since -0.2 rotations has the same absolute position as 0.8
2483 * rotations, we can say that the arm typically does not travel in the
2484 * range (0.6, 0.8) rotations. As a result, the discontinuity point
2485 * would be the center of that range, which is 0.7 rotations. This
2486 * results in an absolute sensor range of [-0.3, 0.7) rotations.
2487 *
2488 * On a Talon motor controller, this is only supported when using the
2489 * PulseWidth sensor source.
2490 *
2491 * - Minimum Value: 0.0
2492 * - Maximum Value: 1.0
2493 * - Default Value: 0.5
2494 * - Units: rotations
2495 *
2496 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
2497 * \returns Itself
2498 */
2499 constexpr ExternalFeedbackConfigs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
2500 {
2501 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
2502 return *this;
2503 }
2504
2505 /**
2506 * \brief Helper method to configure this feedback group to use
2507 * RemoteCANcoder by passing in the CANcoder object.
2508 *
2509 * When using RemoteCANcoder, the Talon will use another
2510 * CANcoder on the same CAN bus. The Talon will update its
2511 * position and velocity whenever CANcoder publishes its
2512 * information on CAN bus, and the Talon commutation sensor
2513 * will not be used.
2514 *
2515 * \param device CANcoder reference to use for RemoteCANcoder
2516 * \returns Itself
2517 */
2519
2520 /**
2521 * \brief Helper method to configure this feedback group to use
2522 * FusedCANcoder by passing in the CANcoder object.
2523 *
2524 * When using FusedCANcoder (requires Phoenix Pro), the Talon
2525 * will fuse another CANcoder's information with the
2526 * commutation sensor, which provides the best possible
2527 * position and velocity for accuracy and bandwidth.
2528 * FusedCANcoder was developed for applications such as
2529 * swerve-azimuth.
2530 *
2531 * \param device CANcoder reference to use for FusedCANcoder
2532 * \returns Itself
2533 */
2535
2536 /**
2537 * \brief Helper method to configure this feedback group to use
2538 * SyncCANcoder by passing in the CANcoder object.
2539 *
2540 * When using SyncCANcoder (requires Phoenix Pro), the Talon
2541 * will synchronize its commutation sensor position against
2542 * another CANcoder, then continue to use the rotor sensor for
2543 * closed loop control. The Talon will report if its internal
2544 * position differs significantly from the reported CANcoder
2545 * position. SyncCANcoder was developed for mechanisms where
2546 * there is a risk of the CANcoder failing in such a way that
2547 * it reports a position that does not match the mechanism,
2548 * such as the sensor mounting assembly breaking off.
2549 *
2550 * \param device CANcoder reference to use for SyncCANcoder
2551 * \returns Itself
2552 */
2554
2555 /**
2556 * \brief Helper method to configure this feedback group to use
2557 * RemoteCANdi PWM 1 by passing in the CANdi object.
2558 *
2559 * \param device CANdi reference to use for RemoteCANdi
2560 * \returns Itself
2561 */
2563
2564 /**
2565 * \brief Helper method to configure this feedback group to use
2566 * RemoteCANdi PWM 2 by passing in the CANdi object.
2567 *
2568 * \param device CANdi reference to use for RemoteCANdi
2569 * \returns Itself
2570 */
2572
2573 /**
2574 * \brief Helper method to configure this feedback group to use
2575 * RemoteCANdi Quadrature by passing in the CANdi object.
2576 *
2577 * \param device CANdi reference to use for RemoteCANdi
2578 * \returns Itself
2579 */
2581
2582 /**
2583 * \brief Helper method to configure this feedback group to use
2584 * FusedCANdi PWM 1 by passing in the CANdi object.
2585 *
2586 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2587 * fuse another CANdi™ branded device's information with the
2588 * internal rotor, which provides the best possible position
2589 * and velocity for accuracy and bandwidth.
2590 *
2591 * \param device CANdi reference to use for FusedCANdi
2592 * \returns Itself
2593 */
2595
2596 /**
2597 * \brief Helper method to configure this feedback group to use
2598 * FusedCANdi PWM 2 by passing in the CANdi object.
2599 *
2600 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2601 * fuse another CANdi™ branded device's information with the
2602 * internal rotor, which provides the best possible position
2603 * and velocity for accuracy and bandwidth.
2604 *
2605 * \param device CANdi reference to use for FusedCANdi
2606 * \returns Itself
2607 */
2609
2610 /**
2611 * \brief Helper method to configure this feedback group to use
2612 * FusedCANdi Quadrature by passing in the CANdi object.
2613 *
2614 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2615 * fuse another CANdi™ branded device's information with the
2616 * internal rotor, which provides the best possible position
2617 * and velocity for accuracy and bandwidth.
2618 *
2619 * \param device CANdi reference to use for FusedCANdi
2620 * \returns Itself
2621 */
2623
2624 /**
2625 * \brief Helper method to configure this feedback group to use
2626 * SyncCANdi PWM 1 by passing in the CANdi object.
2627 *
2628 * When using SyncCANdi (requires Phoenix Pro), the Talon will
2629 * synchronize its internal rotor position against another
2630 * CANdi™ branded device, then continue to use the rotor sensor
2631 * for closed loop control. The Talon will report if its
2632 * internal position differs significantly from the reported
2633 * CANdi™ branded device's position. SyncCANdi was developed
2634 * for mechanisms where there is a risk of the CANdi™ branded
2635 * device failing in such a way that it reports a position that
2636 * does not match the mechanism, such as the sensor mounting
2637 * assembly breaking off.
2638 *
2639 * \param device CANdi reference to use for SyncCANdi
2640 * \returns Itself
2641 */
2643
2644 /**
2645 * \brief Helper method to configure this feedback group to use
2646 * SyncCANdi PWM 2 by passing in the CANdi object.
2647 *
2648 * When using SyncCANdi (requires Phoenix Pro), the Talon will
2649 * synchronize its internal rotor position against another
2650 * CANdi™ branded device, then continue to use the rotor sensor
2651 * for closed loop control. The Talon will report if its
2652 * internal position differs significantly from the reported
2653 * CANdi™ branded device's position. SyncCANdi was developed
2654 * for mechanisms where there is a risk of the CANdi™ branded
2655 * device failing in such a way that it reports a position that
2656 * does not match the mechanism, such as the sensor mounting
2657 * assembly breaking off.
2658 *
2659 * \param device CANdi reference to use for SyncCANdi
2660 * \returns Itself
2661 */
2663
2664
2665
2666 std::string ToString() const override
2667 {
2668 std::stringstream ss;
2669 ss << "Config Group: ExternalFeedback" << std::endl;
2670 ss << " SensorToMechanismRatio: " << SensorToMechanismRatio.to<double>() << " scalar" << std::endl;
2671 ss << " RotorToSensorRatio: " << RotorToSensorRatio.to<double>() << " scalar" << std::endl;
2672 ss << " FeedbackRemoteSensorID: " << FeedbackRemoteSensorID << std::endl;
2673 ss << " VelocityFilterTimeConstant: " << VelocityFilterTimeConstant.to<double>() << " seconds" << std::endl;
2674 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
2675 ss << " ExternalFeedbackSensorSource: " << ExternalFeedbackSensorSource << std::endl;
2676 ss << " SensorPhase: " << SensorPhase << std::endl;
2677 ss << " QuadratureEdgesPerRotation: " << QuadratureEdgesPerRotation << std::endl;
2678 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
2679 return ss.str();
2680 }
2681
2682 std::string Serialize() const override
2683 {
2684 std::stringstream ss;
2685 char *ref;
2686 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, SensorToMechanismRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2687 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, RotorToSensorRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2688 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, FeedbackRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2689 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, VelocityFilterTimeConstant.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2690 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2691 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ExternalFeedbackSensorSource, ExternalFeedbackSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2692 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_SensorPhase, SensorPhase.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2693 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, QuadratureEdgesPerRotation, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2694 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2695 return ss.str();
2696 }
2697
2698 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
2699 {
2700 const char *string_c_str = to_deserialize.c_str();
2701 size_t string_length = to_deserialize.length();
2702 double SensorToMechanismRatioVal = SensorToMechanismRatio.to<double>();
2703 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, string_c_str, string_length, &SensorToMechanismRatioVal);
2704 SensorToMechanismRatio = units::dimensionless::scalar_t{SensorToMechanismRatioVal};
2705 double RotorToSensorRatioVal = RotorToSensorRatio.to<double>();
2706 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, string_c_str, string_length, &RotorToSensorRatioVal);
2707 RotorToSensorRatio = units::dimensionless::scalar_t{RotorToSensorRatioVal};
2708 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, string_c_str, string_length, &FeedbackRemoteSensorID);
2709 double VelocityFilterTimeConstantVal = VelocityFilterTimeConstant.to<double>();
2710 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, string_c_str, string_length, &VelocityFilterTimeConstantVal);
2711 VelocityFilterTimeConstant = units::time::second_t{VelocityFilterTimeConstantVal};
2712 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
2713 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
2714 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
2715 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ExternalFeedbackSensorSource, string_c_str, string_length, &ExternalFeedbackSensorSource.value);
2716 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_SensorPhase, string_c_str, string_length, &SensorPhase.value);
2717 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, string_c_str, string_length, &QuadratureEdgesPerRotation);
2718 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
2719 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
2720 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
2721 return 0;
2722 }
2723};
2724
2725
2726/**
2727 * \brief Configs related to sensors used for differential control of
2728 * a mechanism.
2729 *
2730 * \details Includes the differential sensor sources and IDs.
2731 */
2733{
2734public:
2735 constexpr DifferentialSensorsConfigs() = default;
2736
2737 /**
2738 * \brief Choose what sensor source is used for differential control
2739 * of a mechanism. The default is Disabled. All other options
2740 * require setting the DifferentialTalonFXSensorID, as the average of
2741 * this Talon FX's sensor and the remote TalonFX's sensor is used for
2742 * the differential controller's primary targets.
2743 *
2744 * Choose RemoteTalonFX_Diff to use another TalonFX on the same CAN
2745 * bus. Talon FX will update its differential position and velocity
2746 * whenever the remote TalonFX publishes its information on CAN bus.
2747 * The differential controller will use the difference between this
2748 * TalonFX's sensor and the remote Talon FX's sensor for the
2749 * differential component of the output.
2750 *
2751 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2752 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2753 * also requires setting DifferentialRemoteSensorID). Talon FX will
2754 * update its differential position to match the selected value
2755 * whenever Pigeon2 publishes its information on CAN bus. Note that
2756 * the Talon FX differential position will be in rotations and not
2757 * degrees.
2758 *
2759 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
2760 * (this also requires setting DifferentialRemoteSensorID). Talon FX
2761 * will update its differential position and velocity to match the
2762 * CANcoder whenever CANcoder publishes its information on CAN bus.
2763 *
2764 */
2766 /**
2767 * \brief Device ID of which remote Talon FX to use. This is used
2768 * when the Differential Sensor Source is not disabled.
2769 *
2770 * - Minimum Value: 0
2771 * - Maximum Value: 62
2772 * - Default Value: 0
2773 * - Units:
2774 */
2776 /**
2777 * \brief Device ID of which remote sensor to use on the differential
2778 * axis. This is used when the Differential Sensor Source is not
2779 * RemoteTalonFX_Diff.
2780 *
2781 * - Minimum Value: 0
2782 * - Maximum Value: 62
2783 * - Default Value: 0
2784 * - Units:
2785 */
2787
2788 /**
2789 * \brief Modifies this configuration's DifferentialSensorSource parameter and returns itself for
2790 * method-chaining and easier to use config API.
2791 *
2792 * Choose what sensor source is used for differential control of a
2793 * mechanism. The default is Disabled. All other options require
2794 * setting the DifferentialTalonFXSensorID, as the average of this
2795 * Talon FX's sensor and the remote TalonFX's sensor is used for the
2796 * differential controller's primary targets.
2797 *
2798 * Choose RemoteTalonFX_Diff to use another TalonFX on the same CAN
2799 * bus. Talon FX will update its differential position and velocity
2800 * whenever the remote TalonFX publishes its information on CAN bus.
2801 * The differential controller will use the difference between this
2802 * TalonFX's sensor and the remote Talon FX's sensor for the
2803 * differential component of the output.
2804 *
2805 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2806 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2807 * also requires setting DifferentialRemoteSensorID). Talon FX will
2808 * update its differential position to match the selected value
2809 * whenever Pigeon2 publishes its information on CAN bus. Note that
2810 * the Talon FX differential position will be in rotations and not
2811 * degrees.
2812 *
2813 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
2814 * (this also requires setting DifferentialRemoteSensorID). Talon FX
2815 * will update its differential position and velocity to match the
2816 * CANcoder whenever CANcoder publishes its information on CAN bus.
2817 *
2818 *
2819 * \param newDifferentialSensorSource Parameter to modify
2820 * \returns Itself
2821 */
2823 {
2824 DifferentialSensorSource = std::move(newDifferentialSensorSource);
2825 return *this;
2826 }
2827
2828 /**
2829 * \brief Modifies this configuration's DifferentialTalonFXSensorID parameter and returns itself for
2830 * method-chaining and easier to use config API.
2831 *
2832 * Device ID of which remote Talon FX to use. This is used when the
2833 * Differential Sensor Source is not disabled.
2834 *
2835 * - Minimum Value: 0
2836 * - Maximum Value: 62
2837 * - Default Value: 0
2838 * - Units:
2839 *
2840 * \param newDifferentialTalonFXSensorID Parameter to modify
2841 * \returns Itself
2842 */
2843 constexpr DifferentialSensorsConfigs &WithDifferentialTalonFXSensorID(int newDifferentialTalonFXSensorID)
2844 {
2845 DifferentialTalonFXSensorID = std::move(newDifferentialTalonFXSensorID);
2846 return *this;
2847 }
2848
2849 /**
2850 * \brief Modifies this configuration's DifferentialRemoteSensorID parameter and returns itself for
2851 * method-chaining and easier to use config API.
2852 *
2853 * Device ID of which remote sensor to use on the differential axis.
2854 * This is used when the Differential Sensor Source is not
2855 * RemoteTalonFX_Diff.
2856 *
2857 * - Minimum Value: 0
2858 * - Maximum Value: 62
2859 * - Default Value: 0
2860 * - Units:
2861 *
2862 * \param newDifferentialRemoteSensorID Parameter to modify
2863 * \returns Itself
2864 */
2865 constexpr DifferentialSensorsConfigs &WithDifferentialRemoteSensorID(int newDifferentialRemoteSensorID)
2866 {
2867 DifferentialRemoteSensorID = std::move(newDifferentialRemoteSensorID);
2868 return *this;
2869 }
2870
2871
2872
2873 std::string ToString() const override
2874 {
2875 std::stringstream ss;
2876 ss << "Config Group: DifferentialSensors" << std::endl;
2877 ss << " DifferentialSensorSource: " << DifferentialSensorSource << std::endl;
2878 ss << " DifferentialTalonFXSensorID: " << DifferentialTalonFXSensorID << std::endl;
2879 ss << " DifferentialRemoteSensorID: " << DifferentialRemoteSensorID << std::endl;
2880 return ss.str();
2881 }
2882
2883 std::string Serialize() const override
2884 {
2885 std::stringstream ss;
2886 char *ref;
2887 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialSensorSource, DifferentialSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2888 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialTalonFXSensorID, DifferentialTalonFXSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2889 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialRemoteSensorID, DifferentialRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2890 return ss.str();
2891 }
2892
2893 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
2894 {
2895 const char *string_c_str = to_deserialize.c_str();
2896 size_t string_length = to_deserialize.length();
2897 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialSensorSource, string_c_str, string_length, &DifferentialSensorSource.value);
2898 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialTalonFXSensorID, string_c_str, string_length, &DifferentialTalonFXSensorID);
2899 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialRemoteSensorID, string_c_str, string_length, &DifferentialRemoteSensorID);
2900 return 0;
2901 }
2902};
2903
2904
2905/**
2906 * \brief Configs related to constants used for differential control
2907 * of a mechanism.
2908 *
2909 * \details Includes the differential peak outputs.
2910 */
2912{
2913public:
2914 constexpr DifferentialConstantsConfigs() = default;
2915
2916 /**
2917 * \brief Maximum differential output during duty cycle based
2918 * differential control modes.
2919 *
2920 * - Minimum Value: 0.0
2921 * - Maximum Value: 2.0
2922 * - Default Value: 2
2923 * - Units: fractional
2924 */
2925 units::dimensionless::scalar_t PeakDifferentialDutyCycle = 2;
2926 /**
2927 * \brief Maximum differential output during voltage based
2928 * differential control modes.
2929 *
2930 * - Minimum Value: 0.0
2931 * - Maximum Value: 32
2932 * - Default Value: 32
2933 * - Units: V
2934 */
2935 units::voltage::volt_t PeakDifferentialVoltage = 32_V;
2936 /**
2937 * \brief Maximum differential output during torque current based
2938 * differential control modes.
2939 *
2940 * - Minimum Value: 0.0
2941 * - Maximum Value: 1600
2942 * - Default Value: 1600
2943 * - Units: A
2944 */
2945 units::current::ampere_t PeakDifferentialTorqueCurrent = 1600_A;
2946
2947 /**
2948 * \brief Modifies this configuration's PeakDifferentialDutyCycle parameter and returns itself for
2949 * method-chaining and easier to use config API.
2950 *
2951 * Maximum differential output during duty cycle based differential
2952 * control modes.
2953 *
2954 * - Minimum Value: 0.0
2955 * - Maximum Value: 2.0
2956 * - Default Value: 2
2957 * - Units: fractional
2958 *
2959 * \param newPeakDifferentialDutyCycle Parameter to modify
2960 * \returns Itself
2961 */
2962 constexpr DifferentialConstantsConfigs &WithPeakDifferentialDutyCycle(units::dimensionless::scalar_t newPeakDifferentialDutyCycle)
2963 {
2964 PeakDifferentialDutyCycle = std::move(newPeakDifferentialDutyCycle);
2965 return *this;
2966 }
2967
2968 /**
2969 * \brief Modifies this configuration's PeakDifferentialVoltage parameter and returns itself for
2970 * method-chaining and easier to use config API.
2971 *
2972 * Maximum differential output during voltage based differential
2973 * control modes.
2974 *
2975 * - Minimum Value: 0.0
2976 * - Maximum Value: 32
2977 * - Default Value: 32
2978 * - Units: V
2979 *
2980 * \param newPeakDifferentialVoltage Parameter to modify
2981 * \returns Itself
2982 */
2983 constexpr DifferentialConstantsConfigs &WithPeakDifferentialVoltage(units::voltage::volt_t newPeakDifferentialVoltage)
2984 {
2985 PeakDifferentialVoltage = std::move(newPeakDifferentialVoltage);
2986 return *this;
2987 }
2988
2989 /**
2990 * \brief Modifies this configuration's PeakDifferentialTorqueCurrent parameter and returns itself for
2991 * method-chaining and easier to use config API.
2992 *
2993 * Maximum differential output during torque current based
2994 * differential control modes.
2995 *
2996 * - Minimum Value: 0.0
2997 * - Maximum Value: 1600
2998 * - Default Value: 1600
2999 * - Units: A
3000 *
3001 * \param newPeakDifferentialTorqueCurrent Parameter to modify
3002 * \returns Itself
3003 */
3004 constexpr DifferentialConstantsConfigs &WithPeakDifferentialTorqueCurrent(units::current::ampere_t newPeakDifferentialTorqueCurrent)
3005 {
3006 PeakDifferentialTorqueCurrent = std::move(newPeakDifferentialTorqueCurrent);
3007 return *this;
3008 }
3009
3010
3011
3012 std::string ToString() const override
3013 {
3014 std::stringstream ss;
3015 ss << "Config Group: DifferentialConstants" << std::endl;
3016 ss << " PeakDifferentialDutyCycle: " << PeakDifferentialDutyCycle.to<double>() << " fractional" << std::endl;
3017 ss << " PeakDifferentialVoltage: " << PeakDifferentialVoltage.to<double>() << " V" << std::endl;
3018 ss << " PeakDifferentialTorqueCurrent: " << PeakDifferentialTorqueCurrent.to<double>() << " A" << std::endl;
3019 return ss.str();
3020 }
3021
3022 std::string Serialize() const override
3023 {
3024 std::stringstream ss;
3025 char *ref;
3026 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffDC, PeakDifferentialDutyCycle.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3027 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffV, PeakDifferentialVoltage.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3028 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffTorqCurr, PeakDifferentialTorqueCurrent.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3029 return ss.str();
3030 }
3031
3032 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3033 {
3034 const char *string_c_str = to_deserialize.c_str();
3035 size_t string_length = to_deserialize.length();
3036 double PeakDifferentialDutyCycleVal = PeakDifferentialDutyCycle.to<double>();
3037 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffDC, string_c_str, string_length, &PeakDifferentialDutyCycleVal);
3038 PeakDifferentialDutyCycle = units::dimensionless::scalar_t{PeakDifferentialDutyCycleVal};
3039 double PeakDifferentialVoltageVal = PeakDifferentialVoltage.to<double>();
3040 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffV, string_c_str, string_length, &PeakDifferentialVoltageVal);
3041 PeakDifferentialVoltage = units::voltage::volt_t{PeakDifferentialVoltageVal};
3042 double PeakDifferentialTorqueCurrentVal = PeakDifferentialTorqueCurrent.to<double>();
3043 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffTorqCurr, string_c_str, string_length, &PeakDifferentialTorqueCurrentVal);
3044 PeakDifferentialTorqueCurrent = units::current::ampere_t{PeakDifferentialTorqueCurrentVal};
3045 return 0;
3046 }
3047};
3048
3049
3050/**
3051 * \brief Configs that affect the open-loop control of this motor
3052 * controller.
3053 *
3054 * \details Open-loop ramp rates for the various control types.
3055 */
3057{
3058public:
3059 constexpr OpenLoopRampsConfigs() = default;
3060
3061 /**
3062 * \brief If non-zero, this determines how much time to ramp from 0%
3063 * output to 100% during the open-loop DutyCycleOut control mode.
3064 *
3065 * This provides an easy way to limit the acceleration of the motor.
3066 * However, the acceleration and current draw of the motor can be
3067 * better restricted using current limits instead of a ramp rate.
3068 *
3069 * - Minimum Value: 0
3070 * - Maximum Value: 1
3071 * - Default Value: 0
3072 * - Units: seconds
3073 */
3074 units::time::second_t DutyCycleOpenLoopRampPeriod = 0_s;
3075 /**
3076 * \brief If non-zero, this determines how much time to ramp from 0V
3077 * output to 12V during the open-loop VoltageOut control mode.
3078 *
3079 * This provides an easy way to limit the acceleration of the motor.
3080 * However, the acceleration and current draw of the motor can be
3081 * better restricted using current limits instead of a ramp rate.
3082 *
3083 * - Minimum Value: 0
3084 * - Maximum Value: 1
3085 * - Default Value: 0
3086 * - Units: seconds
3087 */
3088 units::time::second_t VoltageOpenLoopRampPeriod = 0_s;
3089 /**
3090 * \brief If non-zero, this determines how much time to ramp from 0A
3091 * output to 300A during the open-loop TorqueCurrent control mode.
3092 *
3093 * Since TorqueCurrent is directly proportional to acceleration, this
3094 * ramp limits jerk instead of acceleration.
3095 *
3096 * - Minimum Value: 0
3097 * - Maximum Value: 10
3098 * - Default Value: 0
3099 * - Units: seconds
3100 */
3101 units::time::second_t TorqueOpenLoopRampPeriod = 0_s;
3102
3103 /**
3104 * \brief Modifies this configuration's DutyCycleOpenLoopRampPeriod parameter and returns itself for
3105 * method-chaining and easier to use config API.
3106 *
3107 * If non-zero, this determines how much time to ramp from 0% output
3108 * to 100% during the open-loop DutyCycleOut control mode.
3109 *
3110 * This provides an easy way to limit the acceleration of the motor.
3111 * However, the acceleration and current draw of the motor can be
3112 * better restricted using current limits instead of a ramp rate.
3113 *
3114 * - Minimum Value: 0
3115 * - Maximum Value: 1
3116 * - Default Value: 0
3117 * - Units: seconds
3118 *
3119 * \param newDutyCycleOpenLoopRampPeriod Parameter to modify
3120 * \returns Itself
3121 */
3122 constexpr OpenLoopRampsConfigs &WithDutyCycleOpenLoopRampPeriod(units::time::second_t newDutyCycleOpenLoopRampPeriod)
3123 {
3124 DutyCycleOpenLoopRampPeriod = std::move(newDutyCycleOpenLoopRampPeriod);
3125 return *this;
3126 }
3127
3128 /**
3129 * \brief Modifies this configuration's VoltageOpenLoopRampPeriod parameter and returns itself for
3130 * method-chaining and easier to use config API.
3131 *
3132 * If non-zero, this determines how much time to ramp from 0V output
3133 * to 12V during the open-loop VoltageOut control mode.
3134 *
3135 * This provides an easy way to limit the acceleration of the motor.
3136 * However, the acceleration and current draw of the motor can be
3137 * better restricted using current limits instead of a ramp rate.
3138 *
3139 * - Minimum Value: 0
3140 * - Maximum Value: 1
3141 * - Default Value: 0
3142 * - Units: seconds
3143 *
3144 * \param newVoltageOpenLoopRampPeriod Parameter to modify
3145 * \returns Itself
3146 */
3147 constexpr OpenLoopRampsConfigs &WithVoltageOpenLoopRampPeriod(units::time::second_t newVoltageOpenLoopRampPeriod)
3148 {
3149 VoltageOpenLoopRampPeriod = std::move(newVoltageOpenLoopRampPeriod);
3150 return *this;
3151 }
3152
3153 /**
3154 * \brief Modifies this configuration's TorqueOpenLoopRampPeriod parameter and returns itself for
3155 * method-chaining and easier to use config API.
3156 *
3157 * If non-zero, this determines how much time to ramp from 0A output
3158 * to 300A during the open-loop TorqueCurrent control mode.
3159 *
3160 * Since TorqueCurrent is directly proportional to acceleration, this
3161 * ramp limits jerk instead of acceleration.
3162 *
3163 * - Minimum Value: 0
3164 * - Maximum Value: 10
3165 * - Default Value: 0
3166 * - Units: seconds
3167 *
3168 * \param newTorqueOpenLoopRampPeriod Parameter to modify
3169 * \returns Itself
3170 */
3171 constexpr OpenLoopRampsConfigs &WithTorqueOpenLoopRampPeriod(units::time::second_t newTorqueOpenLoopRampPeriod)
3172 {
3173 TorqueOpenLoopRampPeriod = std::move(newTorqueOpenLoopRampPeriod);
3174 return *this;
3175 }
3176
3177
3178
3179 std::string ToString() const override
3180 {
3181 std::stringstream ss;
3182 ss << "Config Group: OpenLoopRamps" << std::endl;
3183 ss << " DutyCycleOpenLoopRampPeriod: " << DutyCycleOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3184 ss << " VoltageOpenLoopRampPeriod: " << VoltageOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3185 ss << " TorqueOpenLoopRampPeriod: " << TorqueOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3186 return ss.str();
3187 }
3188
3189 std::string Serialize() const override
3190 {
3191 std::stringstream ss;
3192 char *ref;
3193 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleOpenLoopRampPeriod, DutyCycleOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3194 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageOpenLoopRampPeriod, VoltageOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3195 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueOpenLoopRampPeriod, TorqueOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3196 return ss.str();
3197 }
3198
3199 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3200 {
3201 const char *string_c_str = to_deserialize.c_str();
3202 size_t string_length = to_deserialize.length();
3203 double DutyCycleOpenLoopRampPeriodVal = DutyCycleOpenLoopRampPeriod.to<double>();
3204 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleOpenLoopRampPeriod, string_c_str, string_length, &DutyCycleOpenLoopRampPeriodVal);
3205 DutyCycleOpenLoopRampPeriod = units::time::second_t{DutyCycleOpenLoopRampPeriodVal};
3206 double VoltageOpenLoopRampPeriodVal = VoltageOpenLoopRampPeriod.to<double>();
3207 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageOpenLoopRampPeriod, string_c_str, string_length, &VoltageOpenLoopRampPeriodVal);
3208 VoltageOpenLoopRampPeriod = units::time::second_t{VoltageOpenLoopRampPeriodVal};
3209 double TorqueOpenLoopRampPeriodVal = TorqueOpenLoopRampPeriod.to<double>();
3210 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueOpenLoopRampPeriod, string_c_str, string_length, &TorqueOpenLoopRampPeriodVal);
3211 TorqueOpenLoopRampPeriod = units::time::second_t{TorqueOpenLoopRampPeriodVal};
3212 return 0;
3213 }
3214};
3215
3216
3217/**
3218 * \brief Configs that affect the closed-loop control of this motor
3219 * controller.
3220 *
3221 * \details Closed-loop ramp rates for the various control types.
3222 */
3224{
3225public:
3226 constexpr ClosedLoopRampsConfigs() = default;
3227
3228 /**
3229 * \brief If non-zero, this determines how much time to ramp from 0%
3230 * output to 100% during the closed-loop DutyCycle control modes.
3231 *
3232 * If the goal is to limit acceleration, it is more useful to ramp the
3233 * closed-loop setpoint instead of the output. This can be achieved
3234 * using Motion Magic® controls.
3235 *
3236 * The acceleration and current draw of the motor can also be better
3237 * restricted using current limits instead of a ramp rate.
3238 *
3239 * - Minimum Value: 0
3240 * - Maximum Value: 1
3241 * - Default Value: 0
3242 * - Units: seconds
3243 */
3244 units::time::second_t DutyCycleClosedLoopRampPeriod = 0_s;
3245 /**
3246 * \brief If non-zero, this determines how much time to ramp from 0V
3247 * output to 12V during the closed-loop Voltage control modes.
3248 *
3249 * If the goal is to limit acceleration, it is more useful to ramp the
3250 * closed-loop setpoint instead of the output. This can be achieved
3251 * using Motion Magic® controls.
3252 *
3253 * The acceleration and current draw of the motor can also be better
3254 * restricted using current limits instead of a ramp rate.
3255 *
3256 * - Minimum Value: 0
3257 * - Maximum Value: 1
3258 * - Default Value: 0
3259 * - Units: seconds
3260 */
3261 units::time::second_t VoltageClosedLoopRampPeriod = 0_s;
3262 /**
3263 * \brief If non-zero, this determines how much time to ramp from 0A
3264 * output to 300A during the closed-loop TorqueCurrent control modes.
3265 *
3266 * Since TorqueCurrent is directly proportional to acceleration, this
3267 * ramp limits jerk instead of acceleration.
3268 *
3269 * If the goal is to limit acceleration or jerk, it is more useful to
3270 * ramp the closed-loop setpoint instead of the output. This can be
3271 * achieved using Motion Magic® controls.
3272 *
3273 * The acceleration and current draw of the motor can also be better
3274 * restricted using current limits instead of a ramp rate.
3275 *
3276 * - Minimum Value: 0
3277 * - Maximum Value: 10
3278 * - Default Value: 0
3279 * - Units: seconds
3280 */
3281 units::time::second_t TorqueClosedLoopRampPeriod = 0_s;
3282
3283 /**
3284 * \brief Modifies this configuration's DutyCycleClosedLoopRampPeriod parameter and returns itself for
3285 * method-chaining and easier to use config API.
3286 *
3287 * If non-zero, this determines how much time to ramp from 0% output
3288 * to 100% during the closed-loop DutyCycle control modes.
3289 *
3290 * If the goal is to limit acceleration, it is more useful to ramp the
3291 * closed-loop setpoint instead of the output. This can be achieved
3292 * using Motion Magic® controls.
3293 *
3294 * The acceleration and current draw of the motor can also be better
3295 * restricted using current limits instead of a ramp rate.
3296 *
3297 * - Minimum Value: 0
3298 * - Maximum Value: 1
3299 * - Default Value: 0
3300 * - Units: seconds
3301 *
3302 * \param newDutyCycleClosedLoopRampPeriod Parameter to modify
3303 * \returns Itself
3304 */
3305 constexpr ClosedLoopRampsConfigs &WithDutyCycleClosedLoopRampPeriod(units::time::second_t newDutyCycleClosedLoopRampPeriod)
3306 {
3307 DutyCycleClosedLoopRampPeriod = std::move(newDutyCycleClosedLoopRampPeriod);
3308 return *this;
3309 }
3310
3311 /**
3312 * \brief Modifies this configuration's VoltageClosedLoopRampPeriod parameter and returns itself for
3313 * method-chaining and easier to use config API.
3314 *
3315 * If non-zero, this determines how much time to ramp from 0V output
3316 * to 12V during the closed-loop Voltage control modes.
3317 *
3318 * If the goal is to limit acceleration, it is more useful to ramp the
3319 * closed-loop setpoint instead of the output. This can be achieved
3320 * using Motion Magic® controls.
3321 *
3322 * The acceleration and current draw of the motor can also be better
3323 * restricted using current limits instead of a ramp rate.
3324 *
3325 * - Minimum Value: 0
3326 * - Maximum Value: 1
3327 * - Default Value: 0
3328 * - Units: seconds
3329 *
3330 * \param newVoltageClosedLoopRampPeriod Parameter to modify
3331 * \returns Itself
3332 */
3333 constexpr ClosedLoopRampsConfigs &WithVoltageClosedLoopRampPeriod(units::time::second_t newVoltageClosedLoopRampPeriod)
3334 {
3335 VoltageClosedLoopRampPeriod = std::move(newVoltageClosedLoopRampPeriod);
3336 return *this;
3337 }
3338
3339 /**
3340 * \brief Modifies this configuration's TorqueClosedLoopRampPeriod parameter and returns itself for
3341 * method-chaining and easier to use config API.
3342 *
3343 * If non-zero, this determines how much time to ramp from 0A output
3344 * to 300A during the closed-loop TorqueCurrent control modes.
3345 *
3346 * Since TorqueCurrent is directly proportional to acceleration, this
3347 * ramp limits jerk instead of acceleration.
3348 *
3349 * If the goal is to limit acceleration or jerk, it is more useful to
3350 * ramp the closed-loop setpoint instead of the output. This can be
3351 * achieved using Motion Magic® controls.
3352 *
3353 * The acceleration and current draw of the motor can also be better
3354 * restricted using current limits instead of a ramp rate.
3355 *
3356 * - Minimum Value: 0
3357 * - Maximum Value: 10
3358 * - Default Value: 0
3359 * - Units: seconds
3360 *
3361 * \param newTorqueClosedLoopRampPeriod Parameter to modify
3362 * \returns Itself
3363 */
3364 constexpr ClosedLoopRampsConfigs &WithTorqueClosedLoopRampPeriod(units::time::second_t newTorqueClosedLoopRampPeriod)
3365 {
3366 TorqueClosedLoopRampPeriod = std::move(newTorqueClosedLoopRampPeriod);
3367 return *this;
3368 }
3369
3370
3371
3372 std::string ToString() const override
3373 {
3374 std::stringstream ss;
3375 ss << "Config Group: ClosedLoopRamps" << std::endl;
3376 ss << " DutyCycleClosedLoopRampPeriod: " << DutyCycleClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3377 ss << " VoltageClosedLoopRampPeriod: " << VoltageClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3378 ss << " TorqueClosedLoopRampPeriod: " << TorqueClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3379 return ss.str();
3380 }
3381
3382 std::string Serialize() const override
3383 {
3384 std::stringstream ss;
3385 char *ref;
3386 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleClosedLoopRampPeriod, DutyCycleClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3387 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageClosedLoopRampPeriod, VoltageClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3388 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueClosedLoopRampPeriod, TorqueClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3389 return ss.str();
3390 }
3391
3392 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3393 {
3394 const char *string_c_str = to_deserialize.c_str();
3395 size_t string_length = to_deserialize.length();
3396 double DutyCycleClosedLoopRampPeriodVal = DutyCycleClosedLoopRampPeriod.to<double>();
3397 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleClosedLoopRampPeriod, string_c_str, string_length, &DutyCycleClosedLoopRampPeriodVal);
3398 DutyCycleClosedLoopRampPeriod = units::time::second_t{DutyCycleClosedLoopRampPeriodVal};
3399 double VoltageClosedLoopRampPeriodVal = VoltageClosedLoopRampPeriod.to<double>();
3400 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageClosedLoopRampPeriod, string_c_str, string_length, &VoltageClosedLoopRampPeriodVal);
3401 VoltageClosedLoopRampPeriod = units::time::second_t{VoltageClosedLoopRampPeriodVal};
3402 double TorqueClosedLoopRampPeriodVal = TorqueClosedLoopRampPeriod.to<double>();
3403 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueClosedLoopRampPeriod, string_c_str, string_length, &TorqueClosedLoopRampPeriodVal);
3404 TorqueClosedLoopRampPeriod = units::time::second_t{TorqueClosedLoopRampPeriodVal};
3405 return 0;
3406 }
3407};
3408
3409
3410/**
3411 * \brief Configs that change how the motor controller behaves under
3412 * different limit switch states.
3413 *
3414 * \details Includes configs such as enabling limit switches,
3415 * configuring the remote sensor ID, the source, and the
3416 * position to set on limit.
3417 */
3419{
3420public:
3421 constexpr HardwareLimitSwitchConfigs() = default;
3422
3423 /**
3424 * \brief Determines if the forward limit switch is normally-open
3425 * (default) or normally-closed.
3426 *
3427 */
3429 /**
3430 * \brief If enabled, the position is automatically set to a specific
3431 * value, specified by ForwardLimitAutosetPositionValue, when the
3432 * forward limit switch is asserted.
3433 *
3434 * - Default Value: False
3435 */
3437 /**
3438 * \brief The value to automatically set the position to when the
3439 * forward limit switch is asserted. This has no effect if
3440 * ForwardLimitAutosetPositionEnable is false.
3441 *
3442 * - Minimum Value: -3.4e+38
3443 * - Maximum Value: 3.4e+38
3444 * - Default Value: 0
3445 * - Units: rotations
3446 */
3447 units::angle::turn_t ForwardLimitAutosetPositionValue = 0_tr;
3448 /**
3449 * \brief If enabled, motor output is set to neutral when the forward
3450 * limit switch is asserted and positive output is requested.
3451 *
3452 * - Default Value: True
3453 */
3455 /**
3456 * \brief Determines where to poll the forward limit switch. This
3457 * defaults to the forward limit switch pin on the limit switch
3458 * connector.
3459 *
3460 * Choose RemoteTalonFX to use the forward limit switch attached to
3461 * another Talon FX on the same CAN bus (this also requires setting
3462 * ForwardLimitRemoteSensorID).
3463 *
3464 * Choose RemoteCANifier to use the forward limit switch attached to
3465 * another CANifier on the same CAN bus (this also requires setting
3466 * ForwardLimitRemoteSensorID).
3467 *
3468 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3469 * (this also requires setting ForwardLimitRemoteSensorID). The
3470 * forward limit will assert when the CANcoder magnet strength changes
3471 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3472 *
3473 */
3475 /**
3476 * \brief Device ID of the remote device if using remote limit switch
3477 * features for the forward limit switch.
3478 *
3479 * - Minimum Value: 0
3480 * - Maximum Value: 62
3481 * - Default Value: 0
3482 * - Units:
3483 */
3485 /**
3486 * \brief Determines if the reverse limit switch is normally-open
3487 * (default) or normally-closed.
3488 *
3489 */
3491 /**
3492 * \brief If enabled, the position is automatically set to a specific
3493 * value, specified by ReverseLimitAutosetPositionValue, when the
3494 * reverse limit switch is asserted.
3495 *
3496 * - Default Value: False
3497 */
3499 /**
3500 * \brief The value to automatically set the position to when the
3501 * reverse limit switch is asserted. This has no effect if
3502 * ReverseLimitAutosetPositionEnable is false.
3503 *
3504 * - Minimum Value: -3.4e+38
3505 * - Maximum Value: 3.4e+38
3506 * - Default Value: 0
3507 * - Units: rotations
3508 */
3509 units::angle::turn_t ReverseLimitAutosetPositionValue = 0_tr;
3510 /**
3511 * \brief If enabled, motor output is set to neutral when reverse
3512 * limit switch is asseted and negative output is requested.
3513 *
3514 * - Default Value: True
3515 */
3517 /**
3518 * \brief Determines where to poll the reverse limit switch. This
3519 * defaults to the reverse limit switch pin on the limit switch
3520 * connector.
3521 *
3522 * Choose RemoteTalonFX to use the reverse limit switch attached to
3523 * another Talon FX on the same CAN bus (this also requires setting
3524 * ReverseLimitRemoteSensorID).
3525 *
3526 * Choose RemoteCANifier to use the reverse limit switch attached to
3527 * another CANifier on the same CAN bus (this also requires setting
3528 * ReverseLimitRemoteSensorID).
3529 *
3530 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3531 * (this also requires setting ReverseLimitRemoteSensorID). The
3532 * reverse limit will assert when the CANcoder magnet strength changes
3533 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3534 *
3535 */
3537 /**
3538 * \brief Device ID of the remote device if using remote limit switch
3539 * features for the reverse limit switch.
3540 *
3541 * - Minimum Value: 0
3542 * - Maximum Value: 62
3543 * - Default Value: 0
3544 * - Units:
3545 */
3547
3548 /**
3549 * \brief Modifies this configuration's ForwardLimitType parameter and returns itself for
3550 * method-chaining and easier to use config API.
3551 *
3552 * Determines if the forward limit switch is normally-open (default)
3553 * or normally-closed.
3554 *
3555 *
3556 * \param newForwardLimitType Parameter to modify
3557 * \returns Itself
3558 */
3560 {
3561 ForwardLimitType = std::move(newForwardLimitType);
3562 return *this;
3563 }
3564
3565 /**
3566 * \brief Modifies this configuration's ForwardLimitAutosetPositionEnable parameter and returns itself for
3567 * method-chaining and easier to use config API.
3568 *
3569 * If enabled, the position is automatically set to a specific value,
3570 * specified by ForwardLimitAutosetPositionValue, when the forward
3571 * limit switch is asserted.
3572 *
3573 * - Default Value: False
3574 *
3575 * \param newForwardLimitAutosetPositionEnable Parameter to modify
3576 * \returns Itself
3577 */
3578 constexpr HardwareLimitSwitchConfigs &WithForwardLimitAutosetPositionEnable(bool newForwardLimitAutosetPositionEnable)
3579 {
3580 ForwardLimitAutosetPositionEnable = std::move(newForwardLimitAutosetPositionEnable);
3581 return *this;
3582 }
3583
3584 /**
3585 * \brief Modifies this configuration's ForwardLimitAutosetPositionValue parameter and returns itself for
3586 * method-chaining and easier to use config API.
3587 *
3588 * The value to automatically set the position to when the forward
3589 * limit switch is asserted. This has no effect if
3590 * ForwardLimitAutosetPositionEnable is false.
3591 *
3592 * - Minimum Value: -3.4e+38
3593 * - Maximum Value: 3.4e+38
3594 * - Default Value: 0
3595 * - Units: rotations
3596 *
3597 * \param newForwardLimitAutosetPositionValue Parameter to modify
3598 * \returns Itself
3599 */
3600 constexpr HardwareLimitSwitchConfigs &WithForwardLimitAutosetPositionValue(units::angle::turn_t newForwardLimitAutosetPositionValue)
3601 {
3602 ForwardLimitAutosetPositionValue = std::move(newForwardLimitAutosetPositionValue);
3603 return *this;
3604 }
3605
3606 /**
3607 * \brief Modifies this configuration's ForwardLimitEnable parameter and returns itself for
3608 * method-chaining and easier to use config API.
3609 *
3610 * If enabled, motor output is set to neutral when the forward limit
3611 * switch is asserted and positive output is requested.
3612 *
3613 * - Default Value: True
3614 *
3615 * \param newForwardLimitEnable Parameter to modify
3616 * \returns Itself
3617 */
3618 constexpr HardwareLimitSwitchConfigs &WithForwardLimitEnable(bool newForwardLimitEnable)
3619 {
3620 ForwardLimitEnable = std::move(newForwardLimitEnable);
3621 return *this;
3622 }
3623
3624 /**
3625 * \brief Modifies this configuration's ForwardLimitSource parameter and returns itself for
3626 * method-chaining and easier to use config API.
3627 *
3628 * Determines where to poll the forward limit switch. This defaults
3629 * to the forward limit switch pin on the limit switch connector.
3630 *
3631 * Choose RemoteTalonFX to use the forward limit switch attached to
3632 * another Talon FX on the same CAN bus (this also requires setting
3633 * ForwardLimitRemoteSensorID).
3634 *
3635 * Choose RemoteCANifier to use the forward limit switch attached to
3636 * another CANifier on the same CAN bus (this also requires setting
3637 * ForwardLimitRemoteSensorID).
3638 *
3639 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3640 * (this also requires setting ForwardLimitRemoteSensorID). The
3641 * forward limit will assert when the CANcoder magnet strength changes
3642 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3643 *
3644 *
3645 * \param newForwardLimitSource Parameter to modify
3646 * \returns Itself
3647 */
3649 {
3650 ForwardLimitSource = std::move(newForwardLimitSource);
3651 return *this;
3652 }
3653
3654 /**
3655 * \brief Modifies this configuration's ForwardLimitRemoteSensorID parameter and returns itself for
3656 * method-chaining and easier to use config API.
3657 *
3658 * Device ID of the remote device if using remote limit switch
3659 * features for the forward limit switch.
3660 *
3661 * - Minimum Value: 0
3662 * - Maximum Value: 62
3663 * - Default Value: 0
3664 * - Units:
3665 *
3666 * \param newForwardLimitRemoteSensorID Parameter to modify
3667 * \returns Itself
3668 */
3669 constexpr HardwareLimitSwitchConfigs &WithForwardLimitRemoteSensorID(int newForwardLimitRemoteSensorID)
3670 {
3671 ForwardLimitRemoteSensorID = std::move(newForwardLimitRemoteSensorID);
3672 return *this;
3673 }
3674
3675 /**
3676 * \brief Modifies this configuration's ReverseLimitType parameter and returns itself for
3677 * method-chaining and easier to use config API.
3678 *
3679 * Determines if the reverse limit switch is normally-open (default)
3680 * or normally-closed.
3681 *
3682 *
3683 * \param newReverseLimitType Parameter to modify
3684 * \returns Itself
3685 */
3687 {
3688 ReverseLimitType = std::move(newReverseLimitType);
3689 return *this;
3690 }
3691
3692 /**
3693 * \brief Modifies this configuration's ReverseLimitAutosetPositionEnable parameter and returns itself for
3694 * method-chaining and easier to use config API.
3695 *
3696 * If enabled, the position is automatically set to a specific value,
3697 * specified by ReverseLimitAutosetPositionValue, when the reverse
3698 * limit switch is asserted.
3699 *
3700 * - Default Value: False
3701 *
3702 * \param newReverseLimitAutosetPositionEnable Parameter to modify
3703 * \returns Itself
3704 */
3705 constexpr HardwareLimitSwitchConfigs &WithReverseLimitAutosetPositionEnable(bool newReverseLimitAutosetPositionEnable)
3706 {
3707 ReverseLimitAutosetPositionEnable = std::move(newReverseLimitAutosetPositionEnable);
3708 return *this;
3709 }
3710
3711 /**
3712 * \brief Modifies this configuration's ReverseLimitAutosetPositionValue parameter and returns itself for
3713 * method-chaining and easier to use config API.
3714 *
3715 * The value to automatically set the position to when the reverse
3716 * limit switch is asserted. This has no effect if
3717 * ReverseLimitAutosetPositionEnable is false.
3718 *
3719 * - Minimum Value: -3.4e+38
3720 * - Maximum Value: 3.4e+38
3721 * - Default Value: 0
3722 * - Units: rotations
3723 *
3724 * \param newReverseLimitAutosetPositionValue Parameter to modify
3725 * \returns Itself
3726 */
3727 constexpr HardwareLimitSwitchConfigs &WithReverseLimitAutosetPositionValue(units::angle::turn_t newReverseLimitAutosetPositionValue)
3728 {
3729 ReverseLimitAutosetPositionValue = std::move(newReverseLimitAutosetPositionValue);
3730 return *this;
3731 }
3732
3733 /**
3734 * \brief Modifies this configuration's ReverseLimitEnable parameter and returns itself for
3735 * method-chaining and easier to use config API.
3736 *
3737 * If enabled, motor output is set to neutral when reverse limit
3738 * switch is asseted and negative output is requested.
3739 *
3740 * - Default Value: True
3741 *
3742 * \param newReverseLimitEnable Parameter to modify
3743 * \returns Itself
3744 */
3745 constexpr HardwareLimitSwitchConfigs &WithReverseLimitEnable(bool newReverseLimitEnable)
3746 {
3747 ReverseLimitEnable = std::move(newReverseLimitEnable);
3748 return *this;
3749 }
3750
3751 /**
3752 * \brief Modifies this configuration's ReverseLimitSource parameter and returns itself for
3753 * method-chaining and easier to use config API.
3754 *
3755 * Determines where to poll the reverse limit switch. This defaults
3756 * to the reverse limit switch pin on the limit switch connector.
3757 *
3758 * Choose RemoteTalonFX to use the reverse limit switch attached to
3759 * another Talon FX on the same CAN bus (this also requires setting
3760 * ReverseLimitRemoteSensorID).
3761 *
3762 * Choose RemoteCANifier to use the reverse limit switch attached to
3763 * another CANifier on the same CAN bus (this also requires setting
3764 * ReverseLimitRemoteSensorID).
3765 *
3766 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3767 * (this also requires setting ReverseLimitRemoteSensorID). The
3768 * reverse limit will assert when the CANcoder magnet strength changes
3769 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3770 *
3771 *
3772 * \param newReverseLimitSource Parameter to modify
3773 * \returns Itself
3774 */
3776 {
3777 ReverseLimitSource = std::move(newReverseLimitSource);
3778 return *this;
3779 }
3780
3781 /**
3782 * \brief Modifies this configuration's ReverseLimitRemoteSensorID parameter and returns itself for
3783 * method-chaining and easier to use config API.
3784 *
3785 * Device ID of the remote device if using remote limit switch
3786 * features for the reverse limit switch.
3787 *
3788 * - Minimum Value: 0
3789 * - Maximum Value: 62
3790 * - Default Value: 0
3791 * - Units:
3792 *
3793 * \param newReverseLimitRemoteSensorID Parameter to modify
3794 * \returns Itself
3795 */
3796 constexpr HardwareLimitSwitchConfigs &WithReverseLimitRemoteSensorID(int newReverseLimitRemoteSensorID)
3797 {
3798 ReverseLimitRemoteSensorID = std::move(newReverseLimitRemoteSensorID);
3799 return *this;
3800 }
3801
3802 /**
3803 * \brief Helper method to configure this feedback group to use
3804 * RemoteTalonFX forward limit switch by passing in the TalonFX
3805 * object. When using RemoteTalonFX, the Talon FX will use the
3806 * forward limit switch attached to another Talon FX on the
3807 * same CAN bus.
3808 *
3809 * \param device TalonFX reference to use for RemoteTalonFX forward limit switch
3810 * \returns Itself
3811 */
3813
3814 /**
3815 * \brief Helper method to configure this feedback group to use
3816 * RemoteCANcoder forward limit switch by passing in the
3817 * CANcoder object. When using RemoteCANcoder, the Talon FX
3818 * will use another CANcoder on the same CAN bus. The forward
3819 * limit will assert when the CANcoder magnet strength changes
3820 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3821 *
3822 * \param device CANcoder reference to use for RemoteCANcoder forward limit switch
3823 * \returns Itself
3824 */
3826
3827 /**
3828 * \brief Helper method to configure this feedback group to use the
3829 * RemoteCANrange by passing in the CANrange object. The
3830 * forward limit will assert when the CANrange proximity detect
3831 * is tripped.
3832 *
3833 * \param device CANrange reference to use for RemoteCANrange forward limit switch
3834 * \returns Itself
3835 */
3837
3838 /**
3839 * \brief Helper method to configure this feedback group to use
3840 * RemoteCANdi forward limit switch on Signal 1 Input (S1IN) by
3841 * passing in the CANdi object. The forward limit will assert
3842 * when the CANdi™ branded device's Signal 1 Input (S1IN) pin
3843 * matches the configured closed state.
3844 *
3845 * \param device CANdi reference to use for RemoteCANdi forward limit switch
3846 * \returns Itself
3847 */
3849
3850 /**
3851 * \brief Helper method to configure this feedback group to use
3852 * RemoteCANdi forward limit switch on Signal 2 Input (S2IN) by
3853 * passing in the CANdi object. The forward limit will assert
3854 * when the CANdi™ branded device's Signal 2 Input (S2IN) pin
3855 * matches the configured closed state.
3856 *
3857 * \param device CANdi reference to use for RemoteCANdi forward limit switch
3858 * \returns Itself
3859 */
3861
3862 /**
3863 * \brief Helper method to configure this feedback group to use
3864 * RemoteTalonFX reverse limit switch by passing in the TalonFX
3865 * object. When using RemoteTalonFX, the Talon FX will use the
3866 * reverse limit switch attached to another Talon FX on the
3867 * same CAN bus.
3868 *
3869 * \param device TalonFX reference to use for RemoteTalonFX reverse limit switch
3870 * \returns Itself
3871 */
3873
3874 /**
3875 * \brief Helper method to configure this feedback group to use
3876 * RemoteCANcoder reverse limit switch by passing in the
3877 * CANcoder object. When using RemoteCANcoder, the Talon FX
3878 * will use another CANcoder on the same CAN bus. The reverse
3879 * limit will assert when the CANcoder magnet strength changes
3880 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3881 *
3882 * \param device CANcoder reference to use for RemoteCANcoder reverse limit switch
3883 * \returns Itself
3884 */
3886
3887 /**
3888 * \brief Helper method to configure this feedback group to use the
3889 * RemoteCANrange by passing in the CANrange object. The
3890 * reverse limit will assert when the CANrange proximity detect
3891 * is tripped.
3892 *
3893 * \param device CANrange reference to use for RemoteCANrange reverse limit switch
3894 * \returns Itself
3895 */
3897
3898 /**
3899 * \brief Helper method to configure this feedback group to use
3900 * RemoteCANdi reverse limit switch on Signal 1 Input (S1IN) by
3901 * passing in the CANdi object. The reverse limit will assert
3902 * when the CANdi™ branded device's Signal 1 Input (S1IN) pin
3903 * matches the configured closed state.
3904 *
3905 * \param device CANdi reference to use for RemoteCANdi reverse limit switch
3906 * \returns Itself
3907 */
3909
3910 /**
3911 * \brief Helper method to configure this feedback group to use
3912 * RemoteCANdi reverse limit switch on Signal 2 Input (S2IN) by
3913 * passing in the CANdi object. The reverse limit will assert
3914 * when the CANdi™ branded device's Signal 2 Input (S2IN) pin
3915 * matches the configured closed state.
3916 *
3917 * \param device CANdi reference to use for RemoteCANdi reverse limit switch
3918 * \returns Itself
3919 */
3921
3922
3923
3924 std::string ToString() const override
3925 {
3926 std::stringstream ss;
3927 ss << "Config Group: HardwareLimitSwitch" << std::endl;
3928 ss << " ForwardLimitType: " << ForwardLimitType << std::endl;
3929 ss << " ForwardLimitAutosetPositionEnable: " << ForwardLimitAutosetPositionEnable << std::endl;
3930 ss << " ForwardLimitAutosetPositionValue: " << ForwardLimitAutosetPositionValue.to<double>() << " rotations" << std::endl;
3931 ss << " ForwardLimitEnable: " << ForwardLimitEnable << std::endl;
3932 ss << " ForwardLimitSource: " << ForwardLimitSource << std::endl;
3933 ss << " ForwardLimitRemoteSensorID: " << ForwardLimitRemoteSensorID << std::endl;
3934 ss << " ReverseLimitType: " << ReverseLimitType << std::endl;
3935 ss << " ReverseLimitAutosetPositionEnable: " << ReverseLimitAutosetPositionEnable << std::endl;
3936 ss << " ReverseLimitAutosetPositionValue: " << ReverseLimitAutosetPositionValue.to<double>() << " rotations" << std::endl;
3937 ss << " ReverseLimitEnable: " << ReverseLimitEnable << std::endl;
3938 ss << " ReverseLimitSource: " << ReverseLimitSource << std::endl;
3939 ss << " ReverseLimitRemoteSensorID: " << ReverseLimitRemoteSensorID << std::endl;
3940 return ss.str();
3941 }
3942
3943 std::string Serialize() const override
3944 {
3945 std::stringstream ss;
3946 char *ref;
3947 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitType, ForwardLimitType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3948 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosEnable, ForwardLimitAutosetPositionEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3949 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosValue, ForwardLimitAutosetPositionValue.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3950 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitEnable, ForwardLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3951 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitSource, ForwardLimitSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3952 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitRemoteSensorID, ForwardLimitRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3953 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitType, ReverseLimitType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3954 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosEnable, ReverseLimitAutosetPositionEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3955 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosValue, ReverseLimitAutosetPositionValue.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3956 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitEnable, ReverseLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3957 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitSource, ReverseLimitSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3958 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitRemoteSensorID, ReverseLimitRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3959 return ss.str();
3960 }
3961
3962 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3963 {
3964 const char *string_c_str = to_deserialize.c_str();
3965 size_t string_length = to_deserialize.length();
3966 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitType, string_c_str, string_length, &ForwardLimitType.value);
3967 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosEnable, string_c_str, string_length, &ForwardLimitAutosetPositionEnable);
3968 double ForwardLimitAutosetPositionValueVal = ForwardLimitAutosetPositionValue.to<double>();
3969 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosValue, string_c_str, string_length, &ForwardLimitAutosetPositionValueVal);
3970 ForwardLimitAutosetPositionValue = units::angle::turn_t{ForwardLimitAutosetPositionValueVal};
3971 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitEnable, string_c_str, string_length, &ForwardLimitEnable);
3972 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitSource, string_c_str, string_length, &ForwardLimitSource.value);
3973 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitRemoteSensorID, string_c_str, string_length, &ForwardLimitRemoteSensorID);
3974 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitType, string_c_str, string_length, &ReverseLimitType.value);
3975 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosEnable, string_c_str, string_length, &ReverseLimitAutosetPositionEnable);
3976 double ReverseLimitAutosetPositionValueVal = ReverseLimitAutosetPositionValue.to<double>();
3977 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosValue, string_c_str, string_length, &ReverseLimitAutosetPositionValueVal);
3978 ReverseLimitAutosetPositionValue = units::angle::turn_t{ReverseLimitAutosetPositionValueVal};
3979 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitEnable, string_c_str, string_length, &ReverseLimitEnable);
3980 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitSource, string_c_str, string_length, &ReverseLimitSource.value);
3981 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitRemoteSensorID, string_c_str, string_length, &ReverseLimitRemoteSensorID);
3982 return 0;
3983 }
3984};
3985
3986
3987/**
3988 * \brief Configs that affect audible components of the device.
3989 *
3990 * \details Includes configuration for the beep on boot.
3991 */
3993{
3994public:
3995 constexpr AudioConfigs() = default;
3996
3997 /**
3998 * \brief If true, the TalonFX will beep during boot-up. This is
3999 * useful for general debugging, and defaults to true. If rotor is
4000 * moving during boot-up, the beep will not occur regardless of this
4001 * setting.
4002 *
4003 * - Default Value: True
4004 */
4005 bool BeepOnBoot = true;
4006 /**
4007 * \brief If true, the TalonFX will beep during configuration API
4008 * calls if device is disabled. This is useful for general debugging,
4009 * and defaults to true. Note that if the rotor is moving, the beep
4010 * will not occur regardless of this setting.
4011 *
4012 * - Default Value: True
4013 */
4014 bool BeepOnConfig = true;
4015 /**
4016 * \brief If true, the TalonFX will allow Orchestra and MusicTone
4017 * requests during disabled state. This can be used to address corner
4018 * cases when music features are needed when disabled. This setting
4019 * defaults to false. Note that if the rotor is moving, music
4020 * features are always disabled regardless of this setting.
4021 *
4022 * - Default Value: False
4023 */
4025
4026 /**
4027 * \brief Modifies this configuration's BeepOnBoot parameter and returns itself for
4028 * method-chaining and easier to use config API.
4029 *
4030 * If true, the TalonFX will beep during boot-up. This is useful for
4031 * general debugging, and defaults to true. If rotor is moving during
4032 * boot-up, the beep will not occur regardless of this setting.
4033 *
4034 * - Default Value: True
4035 *
4036 * \param newBeepOnBoot Parameter to modify
4037 * \returns Itself
4038 */
4039 constexpr AudioConfigs &WithBeepOnBoot(bool newBeepOnBoot)
4040 {
4041 BeepOnBoot = std::move(newBeepOnBoot);
4042 return *this;
4043 }
4044
4045 /**
4046 * \brief Modifies this configuration's BeepOnConfig parameter and returns itself for
4047 * method-chaining and easier to use config API.
4048 *
4049 * If true, the TalonFX will beep during configuration API calls if
4050 * device is disabled. This is useful for general debugging, and
4051 * defaults to true. Note that if the rotor is moving, the beep will
4052 * not occur regardless of this setting.
4053 *
4054 * - Default Value: True
4055 *
4056 * \param newBeepOnConfig Parameter to modify
4057 * \returns Itself
4058 */
4059 constexpr AudioConfigs &WithBeepOnConfig(bool newBeepOnConfig)
4060 {
4061 BeepOnConfig = std::move(newBeepOnConfig);
4062 return *this;
4063 }
4064
4065 /**
4066 * \brief Modifies this configuration's AllowMusicDurDisable parameter and returns itself for
4067 * method-chaining and easier to use config API.
4068 *
4069 * If true, the TalonFX will allow Orchestra and MusicTone requests
4070 * during disabled state. This can be used to address corner cases
4071 * when music features are needed when disabled. This setting
4072 * defaults to false. Note that if the rotor is moving, music
4073 * features are always disabled regardless of this setting.
4074 *
4075 * - Default Value: False
4076 *
4077 * \param newAllowMusicDurDisable Parameter to modify
4078 * \returns Itself
4079 */
4080 constexpr AudioConfigs &WithAllowMusicDurDisable(bool newAllowMusicDurDisable)
4081 {
4082 AllowMusicDurDisable = std::move(newAllowMusicDurDisable);
4083 return *this;
4084 }
4085
4086
4087
4088 std::string ToString() const override
4089 {
4090 std::stringstream ss;
4091 ss << "Config Group: Audio" << std::endl;
4092 ss << " BeepOnBoot: " << BeepOnBoot << std::endl;
4093 ss << " BeepOnConfig: " << BeepOnConfig << std::endl;
4094 ss << " AllowMusicDurDisable: " << AllowMusicDurDisable << std::endl;
4095 return ss.str();
4096 }
4097
4098 std::string Serialize() const override
4099 {
4100 std::stringstream ss;
4101 char *ref;
4102 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnBoot, BeepOnBoot, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4103 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnConfig, BeepOnConfig, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4104 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_AllowMusicDurDisable, AllowMusicDurDisable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4105 return ss.str();
4106 }
4107
4108 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4109 {
4110 const char *string_c_str = to_deserialize.c_str();
4111 size_t string_length = to_deserialize.length();
4112 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnBoot, string_c_str, string_length, &BeepOnBoot);
4113 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnConfig, string_c_str, string_length, &BeepOnConfig);
4114 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_AllowMusicDurDisable, string_c_str, string_length, &AllowMusicDurDisable);
4115 return 0;
4116 }
4117};
4118
4119
4120/**
4121 * \brief Configs that affect how software-limit switches behave.
4122 *
4123 * \details Includes enabling software-limit switches and the
4124 * threshold at which they are tripped.
4125 */
4127{
4128public:
4129 constexpr SoftwareLimitSwitchConfigs() = default;
4130
4131 /**
4132 * \brief If enabled, the motor output is set to neutral if position
4133 * exceeds ForwardSoftLimitThreshold and forward output is requested.
4134 *
4135 * - Default Value: False
4136 */
4138 /**
4139 * \brief If enabled, the motor output is set to neutral if position
4140 * exceeds ReverseSoftLimitThreshold and reverse output is requested.
4141 *
4142 * - Default Value: False
4143 */
4145 /**
4146 * \brief Position threshold for forward soft limit features.
4147 * ForwardSoftLimitEnable must be enabled for this to take effect.
4148 *
4149 * - Minimum Value: -3.4e+38
4150 * - Maximum Value: 3.4e+38
4151 * - Default Value: 0
4152 * - Units: rotations
4153 */
4154 units::angle::turn_t ForwardSoftLimitThreshold = 0_tr;
4155 /**
4156 * \brief Position threshold for reverse soft limit features.
4157 * ReverseSoftLimitEnable must be enabled for this to take effect.
4158 *
4159 * - Minimum Value: -3.4e+38
4160 * - Maximum Value: 3.4e+38
4161 * - Default Value: 0
4162 * - Units: rotations
4163 */
4164 units::angle::turn_t ReverseSoftLimitThreshold = 0_tr;
4165
4166 /**
4167 * \brief Modifies this configuration's ForwardSoftLimitEnable parameter and returns itself for
4168 * method-chaining and easier to use config API.
4169 *
4170 * If enabled, the motor output is set to neutral if position exceeds
4171 * ForwardSoftLimitThreshold and forward output is requested.
4172 *
4173 * - Default Value: False
4174 *
4175 * \param newForwardSoftLimitEnable Parameter to modify
4176 * \returns Itself
4177 */
4178 constexpr SoftwareLimitSwitchConfigs &WithForwardSoftLimitEnable(bool newForwardSoftLimitEnable)
4179 {
4180 ForwardSoftLimitEnable = std::move(newForwardSoftLimitEnable);
4181 return *this;
4182 }
4183
4184 /**
4185 * \brief Modifies this configuration's ReverseSoftLimitEnable parameter and returns itself for
4186 * method-chaining and easier to use config API.
4187 *
4188 * If enabled, the motor output is set to neutral if position exceeds
4189 * ReverseSoftLimitThreshold and reverse output is requested.
4190 *
4191 * - Default Value: False
4192 *
4193 * \param newReverseSoftLimitEnable Parameter to modify
4194 * \returns Itself
4195 */
4196 constexpr SoftwareLimitSwitchConfigs &WithReverseSoftLimitEnable(bool newReverseSoftLimitEnable)
4197 {
4198 ReverseSoftLimitEnable = std::move(newReverseSoftLimitEnable);
4199 return *this;
4200 }
4201
4202 /**
4203 * \brief Modifies this configuration's ForwardSoftLimitThreshold parameter and returns itself for
4204 * method-chaining and easier to use config API.
4205 *
4206 * Position threshold for forward soft limit features.
4207 * ForwardSoftLimitEnable must be enabled for this to take effect.
4208 *
4209 * - Minimum Value: -3.4e+38
4210 * - Maximum Value: 3.4e+38
4211 * - Default Value: 0
4212 * - Units: rotations
4213 *
4214 * \param newForwardSoftLimitThreshold Parameter to modify
4215 * \returns Itself
4216 */
4217 constexpr SoftwareLimitSwitchConfigs &WithForwardSoftLimitThreshold(units::angle::turn_t newForwardSoftLimitThreshold)
4218 {
4219 ForwardSoftLimitThreshold = std::move(newForwardSoftLimitThreshold);
4220 return *this;
4221 }
4222
4223 /**
4224 * \brief Modifies this configuration's ReverseSoftLimitThreshold parameter and returns itself for
4225 * method-chaining and easier to use config API.
4226 *
4227 * Position threshold for reverse soft limit features.
4228 * ReverseSoftLimitEnable must be enabled for this to take effect.
4229 *
4230 * - Minimum Value: -3.4e+38
4231 * - Maximum Value: 3.4e+38
4232 * - Default Value: 0
4233 * - Units: rotations
4234 *
4235 * \param newReverseSoftLimitThreshold Parameter to modify
4236 * \returns Itself
4237 */
4238 constexpr SoftwareLimitSwitchConfigs &WithReverseSoftLimitThreshold(units::angle::turn_t newReverseSoftLimitThreshold)
4239 {
4240 ReverseSoftLimitThreshold = std::move(newReverseSoftLimitThreshold);
4241 return *this;
4242 }
4243
4244
4245
4246 std::string ToString() const override
4247 {
4248 std::stringstream ss;
4249 ss << "Config Group: SoftwareLimitSwitch" << std::endl;
4250 ss << " ForwardSoftLimitEnable: " << ForwardSoftLimitEnable << std::endl;
4251 ss << " ReverseSoftLimitEnable: " << ReverseSoftLimitEnable << std::endl;
4252 ss << " ForwardSoftLimitThreshold: " << ForwardSoftLimitThreshold.to<double>() << " rotations" << std::endl;
4253 ss << " ReverseSoftLimitThreshold: " << ReverseSoftLimitThreshold.to<double>() << " rotations" << std::endl;
4254 return ss.str();
4255 }
4256
4257 std::string Serialize() const override
4258 {
4259 std::stringstream ss;
4260 char *ref;
4261 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitEnable, ForwardSoftLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4262 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitEnable, ReverseSoftLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4263 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitThreshold, ForwardSoftLimitThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4264 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitThreshold, ReverseSoftLimitThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4265 return ss.str();
4266 }
4267
4268 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4269 {
4270 const char *string_c_str = to_deserialize.c_str();
4271 size_t string_length = to_deserialize.length();
4272 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitEnable, string_c_str, string_length, &ForwardSoftLimitEnable);
4273 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitEnable, string_c_str, string_length, &ReverseSoftLimitEnable);
4274 double ForwardSoftLimitThresholdVal = ForwardSoftLimitThreshold.to<double>();
4275 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitThreshold, string_c_str, string_length, &ForwardSoftLimitThresholdVal);
4276 ForwardSoftLimitThreshold = units::angle::turn_t{ForwardSoftLimitThresholdVal};
4277 double ReverseSoftLimitThresholdVal = ReverseSoftLimitThreshold.to<double>();
4278 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitThreshold, string_c_str, string_length, &ReverseSoftLimitThresholdVal);
4279 ReverseSoftLimitThreshold = units::angle::turn_t{ReverseSoftLimitThresholdVal};
4280 return 0;
4281 }
4282};
4283
4284
4285/**
4286 * \brief Configs for Motion Magic®.
4287 *
4288 * \details Includes Velocity, Acceleration, Jerk, and Expo
4289 * parameters.
4290 */
4292{
4293public:
4294 constexpr MotionMagicConfigs() = default;
4295
4296 /**
4297 * \brief This is the maximum velocity Motion Magic® based control
4298 * modes are allowed to use. Motion Magic® Velocity control modes do
4299 * not use this config.
4300 *
4301 * When using Motion Magic® Expo control modes, setting this to 0 will
4302 * allow the profile to run to the max possible velocity based on
4303 * Expo_kV.
4304 *
4305 * - Minimum Value: 0
4306 * - Maximum Value: 9999
4307 * - Default Value: 0
4308 * - Units: rot per sec
4309 */
4310 units::angular_velocity::turns_per_second_t MotionMagicCruiseVelocity = 0_tps;
4311 /**
4312 * \brief This is the target acceleration Motion Magic® based control
4313 * modes are allowed to use. Motion Magic® Expo control modes do not
4314 * use this config.
4315 *
4316 * - Minimum Value: 0
4317 * - Maximum Value: 9999
4318 * - Default Value: 0
4319 * - Units: rot per sec²
4320 */
4321 units::angular_acceleration::turns_per_second_squared_t MotionMagicAcceleration = 0_tr_per_s_sq;
4322 /**
4323 * \brief This is the target jerk (acceleration derivative) Motion
4324 * Magic® based control modes are allowed to use. Motion Magic® Expo
4325 * control modes do not use this config. This allows Motion Magic® to
4326 * generate S-Curve profiles.
4327 *
4328 * Jerk is optional; if this is set to zero, then Motion Magic® will
4329 * not apply a Jerk limit.
4330 *
4331 * - Minimum Value: 0
4332 * - Maximum Value: 9999
4333 * - Default Value: 0
4334 * - Units: rot per sec³
4335 */
4336 units::angular_jerk::turns_per_second_cubed_t MotionMagicJerk = 0_tr_per_s_cu;
4337 /**
4338 * \brief This is the target kV used only by Motion Magic® Expo
4339 * control modes. Unlike the kV slot gain, this is always in units of
4340 * V/rps.
4341 *
4342 * This represents the amount of voltage necessary to hold a velocity.
4343 * In terms of the Motion Magic® Expo profile, a higher kV results in
4344 * a slower maximum velocity.
4345 *
4346 * - Minimum Value: 0.001
4347 * - Maximum Value: 100
4348 * - Default Value: 0.12
4349 * - Units: V/rps
4350 */
4351 ctre::unit::volts_per_turn_per_second_t MotionMagicExpo_kV = 0.12_V / 1_tps;
4352 /**
4353 * \brief This is the target kA used only by Motion Magic® Expo
4354 * control modes. Unlike the kA slot gain, this is always in units of
4355 * V/rps².
4356 *
4357 * This represents the amount of voltage necessary to achieve an
4358 * acceleration. In terms of the Motion Magic® Expo profile, a higher
4359 * kA results in a slower acceleration.
4360 *
4361 * - Minimum Value: 1e-05
4362 * - Maximum Value: 100
4363 * - Default Value: 0.1
4364 * - Units: V/rps²
4365 */
4366 ctre::unit::volts_per_turn_per_second_squared_t MotionMagicExpo_kA = 0.1_V / 1_tr_per_s_sq;
4367
4368 /**
4369 * \brief Modifies this configuration's MotionMagicCruiseVelocity parameter and returns itself for
4370 * method-chaining and easier to use config API.
4371 *
4372 * This is the maximum velocity Motion Magic® based control modes are
4373 * allowed to use. Motion Magic® Velocity control modes do not use
4374 * this config.
4375 *
4376 * When using Motion Magic® Expo control modes, setting this to 0 will
4377 * allow the profile to run to the max possible velocity based on
4378 * Expo_kV.
4379 *
4380 * - Minimum Value: 0
4381 * - Maximum Value: 9999
4382 * - Default Value: 0
4383 * - Units: rot per sec
4384 *
4385 * \param newMotionMagicCruiseVelocity Parameter to modify
4386 * \returns Itself
4387 */
4388 constexpr MotionMagicConfigs &WithMotionMagicCruiseVelocity(units::angular_velocity::turns_per_second_t newMotionMagicCruiseVelocity)
4389 {
4390 MotionMagicCruiseVelocity = std::move(newMotionMagicCruiseVelocity);
4391 return *this;
4392 }
4393
4394 /**
4395 * \brief Modifies this configuration's MotionMagicAcceleration parameter and returns itself for
4396 * method-chaining and easier to use config API.
4397 *
4398 * This is the target acceleration Motion Magic® based control modes
4399 * are allowed to use. Motion Magic® Expo control modes do not use
4400 * this config.
4401 *
4402 * - Minimum Value: 0
4403 * - Maximum Value: 9999
4404 * - Default Value: 0
4405 * - Units: rot per sec²
4406 *
4407 * \param newMotionMagicAcceleration Parameter to modify
4408 * \returns Itself
4409 */
4410 constexpr MotionMagicConfigs &WithMotionMagicAcceleration(units::angular_acceleration::turns_per_second_squared_t newMotionMagicAcceleration)
4411 {
4412 MotionMagicAcceleration = std::move(newMotionMagicAcceleration);
4413 return *this;
4414 }
4415
4416 /**
4417 * \brief Modifies this configuration's MotionMagicJerk parameter and returns itself for
4418 * method-chaining and easier to use config API.
4419 *
4420 * This is the target jerk (acceleration derivative) Motion Magic®
4421 * based control modes are allowed to use. Motion Magic® Expo control
4422 * modes do not use this config. This allows Motion Magic® to
4423 * generate S-Curve profiles.
4424 *
4425 * Jerk is optional; if this is set to zero, then Motion Magic® will
4426 * not apply a Jerk limit.
4427 *
4428 * - Minimum Value: 0
4429 * - Maximum Value: 9999
4430 * - Default Value: 0
4431 * - Units: rot per sec³
4432 *
4433 * \param newMotionMagicJerk Parameter to modify
4434 * \returns Itself
4435 */
4436 constexpr MotionMagicConfigs &WithMotionMagicJerk(units::angular_jerk::turns_per_second_cubed_t newMotionMagicJerk)
4437 {
4438 MotionMagicJerk = std::move(newMotionMagicJerk);
4439 return *this;
4440 }
4441
4442 /**
4443 * \brief Modifies this configuration's MotionMagicExpo_kV parameter and returns itself for
4444 * method-chaining and easier to use config API.
4445 *
4446 * This is the target kV used only by Motion Magic® Expo control
4447 * modes. Unlike the kV slot gain, this is always in units of V/rps.
4448 *
4449 * This represents the amount of voltage necessary to hold a velocity.
4450 * In terms of the Motion Magic® Expo profile, a higher kV results in
4451 * a slower maximum velocity.
4452 *
4453 * - Minimum Value: 0.001
4454 * - Maximum Value: 100
4455 * - Default Value: 0.12
4456 * - Units: V/rps
4457 *
4458 * \param newMotionMagicExpo_kV Parameter to modify
4459 * \returns Itself
4460 */
4461 constexpr MotionMagicConfigs &WithMotionMagicExpo_kV(ctre::unit::volts_per_turn_per_second_t newMotionMagicExpo_kV)
4462 {
4463 MotionMagicExpo_kV = std::move(newMotionMagicExpo_kV);
4464 return *this;
4465 }
4466
4467 /**
4468 * \brief Modifies this configuration's MotionMagicExpo_kA parameter and returns itself for
4469 * method-chaining and easier to use config API.
4470 *
4471 * This is the target kA used only by Motion Magic® Expo control
4472 * modes. Unlike the kA slot gain, this is always in units of V/rps².
4473 *
4474 * This represents the amount of voltage necessary to achieve an
4475 * acceleration. In terms of the Motion Magic® Expo profile, a higher
4476 * kA results in a slower acceleration.
4477 *
4478 * - Minimum Value: 1e-05
4479 * - Maximum Value: 100
4480 * - Default Value: 0.1
4481 * - Units: V/rps²
4482 *
4483 * \param newMotionMagicExpo_kA Parameter to modify
4484 * \returns Itself
4485 */
4486 constexpr MotionMagicConfigs &WithMotionMagicExpo_kA(ctre::unit::volts_per_turn_per_second_squared_t newMotionMagicExpo_kA)
4487 {
4488 MotionMagicExpo_kA = std::move(newMotionMagicExpo_kA);
4489 return *this;
4490 }
4491
4492
4493
4494 std::string ToString() const override
4495 {
4496 std::stringstream ss;
4497 ss << "Config Group: MotionMagic" << std::endl;
4498 ss << " MotionMagicCruiseVelocity: " << MotionMagicCruiseVelocity.to<double>() << " rot per sec" << std::endl;
4499 ss << " MotionMagicAcceleration: " << MotionMagicAcceleration.to<double>() << " rot per sec²" << std::endl;
4500 ss << " MotionMagicJerk: " << MotionMagicJerk.to<double>() << " rot per sec³" << std::endl;
4501 ss << " MotionMagicExpo_kV: " << MotionMagicExpo_kV.to<double>() << " V/rps" << std::endl;
4502 ss << " MotionMagicExpo_kA: " << MotionMagicExpo_kA.to<double>() << " V/rps²" << std::endl;
4503 return ss.str();
4504 }
4505
4506 std::string Serialize() const override
4507 {
4508 std::stringstream ss;
4509 char *ref;
4510 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicCruiseVelocity, MotionMagicCruiseVelocity.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4511 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicAcceleration, MotionMagicAcceleration.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4512 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicJerk, MotionMagicJerk.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4513 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kV, MotionMagicExpo_kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4514 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kA, MotionMagicExpo_kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4515 return ss.str();
4516 }
4517
4518 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4519 {
4520 const char *string_c_str = to_deserialize.c_str();
4521 size_t string_length = to_deserialize.length();
4522 double MotionMagicCruiseVelocityVal = MotionMagicCruiseVelocity.to<double>();
4523 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicCruiseVelocity, string_c_str, string_length, &MotionMagicCruiseVelocityVal);
4524 MotionMagicCruiseVelocity = units::angular_velocity::turns_per_second_t{MotionMagicCruiseVelocityVal};
4525 double MotionMagicAccelerationVal = MotionMagicAcceleration.to<double>();
4526 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicAcceleration, string_c_str, string_length, &MotionMagicAccelerationVal);
4527 MotionMagicAcceleration = units::angular_acceleration::turns_per_second_squared_t{MotionMagicAccelerationVal};
4528 double MotionMagicJerkVal = MotionMagicJerk.to<double>();
4529 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicJerk, string_c_str, string_length, &MotionMagicJerkVal);
4530 MotionMagicJerk = units::angular_jerk::turns_per_second_cubed_t{MotionMagicJerkVal};
4531 double MotionMagicExpo_kVVal = MotionMagicExpo_kV.to<double>();
4532 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kV, string_c_str, string_length, &MotionMagicExpo_kVVal);
4533 MotionMagicExpo_kV = ctre::unit::volts_per_turn_per_second_t{MotionMagicExpo_kVVal};
4534 double MotionMagicExpo_kAVal = MotionMagicExpo_kA.to<double>();
4535 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kA, string_c_str, string_length, &MotionMagicExpo_kAVal);
4536 MotionMagicExpo_kA = ctre::unit::volts_per_turn_per_second_squared_t{MotionMagicExpo_kAVal};
4537 return 0;
4538 }
4539};
4540
4541
4542/**
4543 * \brief Custom Params.
4544 *
4545 * \details Custom paramaters that have no real impact on controller.
4546 */
4548{
4549public:
4550 constexpr CustomParamsConfigs() = default;
4551
4552 /**
4553 * \brief Custom parameter 0. This is provided to allow
4554 * end-applications to store persistent information in the device.
4555 *
4556 * - Minimum Value: -32768
4557 * - Maximum Value: 32767
4558 * - Default Value: 0
4559 * - Units:
4560 */
4562 /**
4563 * \brief Custom parameter 1. This is provided to allow
4564 * end-applications to store persistent information in the device.
4565 *
4566 * - Minimum Value: -32768
4567 * - Maximum Value: 32767
4568 * - Default Value: 0
4569 * - Units:
4570 */
4572
4573 /**
4574 * \brief Modifies this configuration's CustomParam0 parameter and returns itself for
4575 * method-chaining and easier to use config API.
4576 *
4577 * Custom parameter 0. This is provided to allow end-applications to
4578 * store persistent information in the device.
4579 *
4580 * - Minimum Value: -32768
4581 * - Maximum Value: 32767
4582 * - Default Value: 0
4583 * - Units:
4584 *
4585 * \param newCustomParam0 Parameter to modify
4586 * \returns Itself
4587 */
4588 constexpr CustomParamsConfigs &WithCustomParam0(int newCustomParam0)
4589 {
4590 CustomParam0 = std::move(newCustomParam0);
4591 return *this;
4592 }
4593
4594 /**
4595 * \brief Modifies this configuration's CustomParam1 parameter and returns itself for
4596 * method-chaining and easier to use config API.
4597 *
4598 * Custom parameter 1. This is provided to allow end-applications to
4599 * store persistent information in the device.
4600 *
4601 * - Minimum Value: -32768
4602 * - Maximum Value: 32767
4603 * - Default Value: 0
4604 * - Units:
4605 *
4606 * \param newCustomParam1 Parameter to modify
4607 * \returns Itself
4608 */
4609 constexpr CustomParamsConfigs &WithCustomParam1(int newCustomParam1)
4610 {
4611 CustomParam1 = std::move(newCustomParam1);
4612 return *this;
4613 }
4614
4615
4616
4617 std::string ToString() const override
4618 {
4619 std::stringstream ss;
4620 ss << "Config Group: CustomParams" << std::endl;
4621 ss << " CustomParam0: " << CustomParam0 << std::endl;
4622 ss << " CustomParam1: " << CustomParam1 << std::endl;
4623 return ss.str();
4624 }
4625
4626 std::string Serialize() const override
4627 {
4628 std::stringstream ss;
4629 char *ref;
4630 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CustomParam0, CustomParam0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4631 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CustomParam1, CustomParam1, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4632 return ss.str();
4633 }
4634
4635 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4636 {
4637 const char *string_c_str = to_deserialize.c_str();
4638 size_t string_length = to_deserialize.length();
4639 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CustomParam0, string_c_str, string_length, &CustomParam0);
4640 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CustomParam1, string_c_str, string_length, &CustomParam1);
4641 return 0;
4642 }
4643};
4644
4645
4646/**
4647 * \brief Configs that affect general behavior during closed-looping.
4648 *
4649 * \details Includes Continuous Wrap features.
4650 */
4652{
4653public:
4654 constexpr ClosedLoopGeneralConfigs() = default;
4655
4656 /**
4657 * \brief Wrap position error within [-0.5,+0.5) mechanism rotations.
4658 * Typically used for continuous position closed-loops like swerve
4659 * azimuth.
4660 *
4661 * \details This uses the mechanism rotation value. If there is a gear
4662 * ratio between the sensor and the mechanism, make sure to apply a
4663 * SensorToMechanismRatio so the closed loop operates on the full
4664 * rotation.
4665 *
4666 * - Default Value: False
4667 */
4668 bool ContinuousWrap = false;
4669
4670 /**
4671 * \brief Modifies this configuration's ContinuousWrap parameter and returns itself for
4672 * method-chaining and easier to use config API.
4673 *
4674 * Wrap position error within [-0.5,+0.5) mechanism rotations.
4675 * Typically used for continuous position closed-loops like swerve
4676 * azimuth.
4677 *
4678 * \details This uses the mechanism rotation value. If there is a gear
4679 * ratio between the sensor and the mechanism, make sure to apply a
4680 * SensorToMechanismRatio so the closed loop operates on the full
4681 * rotation.
4682 *
4683 * - Default Value: False
4684 *
4685 * \param newContinuousWrap Parameter to modify
4686 * \returns Itself
4687 */
4688 constexpr ClosedLoopGeneralConfigs &WithContinuousWrap(bool newContinuousWrap)
4689 {
4690 ContinuousWrap = std::move(newContinuousWrap);
4691 return *this;
4692 }
4693
4694
4695
4696 std::string ToString() const override
4697 {
4698 std::stringstream ss;
4699 ss << "Config Group: ClosedLoopGeneral" << std::endl;
4700 ss << " ContinuousWrap: " << ContinuousWrap << std::endl;
4701 return ss.str();
4702 }
4703
4704 std::string Serialize() const override
4705 {
4706 std::stringstream ss;
4707 char *ref;
4708 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ContinuousWrap, ContinuousWrap, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4709 return ss.str();
4710 }
4711
4712 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4713 {
4714 const char *string_c_str = to_deserialize.c_str();
4715 size_t string_length = to_deserialize.length();
4716 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ContinuousWrap, string_c_str, string_length, &ContinuousWrap);
4717 return 0;
4718 }
4719};
4720
4721
4722/**
4723 * \brief Configs that affect the ToF sensor
4724 *
4725 * \details Includes Update mode and frequency
4726 */
4728{
4729public:
4730 constexpr ToFParamsConfigs() = default;
4731
4732 /**
4733 * \brief Update mode of the CANrange. The CANrange supports
4734 * short-range and long-range detection at various update frequencies.
4735 *
4736 */
4738 /**
4739 * \brief Rate at which the CANrange will take measurements. A lower
4740 * frequency may provide more stable readings but will reduce the data
4741 * rate of the sensor.
4742 *
4743 * - Minimum Value: 5
4744 * - Maximum Value: 50
4745 * - Default Value: 50
4746 * - Units: Hz
4747 */
4748 units::frequency::hertz_t UpdateFrequency = 50_Hz;
4749
4750 /**
4751 * \brief Modifies this configuration's UpdateMode parameter and returns itself for
4752 * method-chaining and easier to use config API.
4753 *
4754 * Update mode of the CANrange. The CANrange supports short-range and
4755 * long-range detection at various update frequencies.
4756 *
4757 *
4758 * \param newUpdateMode Parameter to modify
4759 * \returns Itself
4760 */
4762 {
4763 UpdateMode = std::move(newUpdateMode);
4764 return *this;
4765 }
4766
4767 /**
4768 * \brief Modifies this configuration's UpdateFrequency parameter and returns itself for
4769 * method-chaining and easier to use config API.
4770 *
4771 * Rate at which the CANrange will take measurements. A lower
4772 * frequency may provide more stable readings but will reduce the data
4773 * rate of the sensor.
4774 *
4775 * - Minimum Value: 5
4776 * - Maximum Value: 50
4777 * - Default Value: 50
4778 * - Units: Hz
4779 *
4780 * \param newUpdateFrequency Parameter to modify
4781 * \returns Itself
4782 */
4783 constexpr ToFParamsConfigs &WithUpdateFrequency(units::frequency::hertz_t newUpdateFrequency)
4784 {
4785 UpdateFrequency = std::move(newUpdateFrequency);
4786 return *this;
4787 }
4788
4789
4790
4791 std::string ToString() const override
4792 {
4793 std::stringstream ss;
4794 ss << "Config Group: ToFParams" << std::endl;
4795 ss << " UpdateMode: " << UpdateMode << std::endl;
4796 ss << " UpdateFrequency: " << UpdateFrequency.to<double>() << " Hz" << std::endl;
4797 return ss.str();
4798 }
4799
4800 std::string Serialize() const override
4801 {
4802 std::stringstream ss;
4803 char *ref;
4804 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANrange_UpdateMode, UpdateMode.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4805 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_UpdateFreq, UpdateFrequency.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4806 return ss.str();
4807 }
4808
4809 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4810 {
4811 const char *string_c_str = to_deserialize.c_str();
4812 size_t string_length = to_deserialize.length();
4813 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANrange_UpdateMode, string_c_str, string_length, &UpdateMode.value);
4814 double UpdateFrequencyVal = UpdateFrequency.to<double>();
4815 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_UpdateFreq, string_c_str, string_length, &UpdateFrequencyVal);
4816 UpdateFrequency = units::frequency::hertz_t{UpdateFrequencyVal};
4817 return 0;
4818 }
4819};
4820
4821
4822/**
4823 * \brief Configs that affect the ToF Proximity detection
4824 *
4825 * \details Includes proximity mode and the threshold for simple
4826 * detection
4827 */
4829{
4830public:
4831 constexpr ProximityParamsConfigs() = default;
4832
4833 /**
4834 * \brief Threshold for object detection.
4835 *
4836 * - Minimum Value: 0
4837 * - Maximum Value: 4
4838 * - Default Value: 0.4
4839 * - Units: m
4840 */
4841 units::length::meter_t ProximityThreshold = 0.4_m;
4842 /**
4843 * \brief How far above and below the threshold the distance needs to
4844 * be to trigger undetected and detected, respectively. This is used
4845 * to prevent bouncing between the detected and undetected states for
4846 * objects on the threshold.
4847 *
4848 * If the threshold is set to 0.1 meters, and the hysteresis is 0.01
4849 * meters, then an object needs to be within 0.09 meters to be
4850 * detected. After the object is first detected, the distance then
4851 * needs to exceed 0.11 meters to become undetected again.
4852 *
4853 * - Minimum Value: 0
4854 * - Maximum Value: 1
4855 * - Default Value: 0.01
4856 * - Units: m
4857 */
4858 units::length::meter_t ProximityHysteresis = 0.01_m;
4859 /**
4860 * \brief The minimum allowable signal strength before determining the
4861 * measurement is valid.
4862 *
4863 * If the signal strength is particularly low, this typically means
4864 * the object is far away and there's fewer total samples to derive
4865 * the distance from. Set this value to be below the lowest strength
4866 * you see when you're detecting an object with the CANrange; the
4867 * default of 2500 is typically acceptable in most cases.
4868 *
4869 * - Minimum Value: 1
4870 * - Maximum Value: 15000
4871 * - Default Value: 2500
4872 * - Units:
4873 */
4874 units::dimensionless::scalar_t MinSignalStrengthForValidMeasurement = 2500;
4875
4876 /**
4877 * \brief Modifies this configuration's ProximityThreshold parameter and returns itself for
4878 * method-chaining and easier to use config API.
4879 *
4880 * Threshold for object detection.
4881 *
4882 * - Minimum Value: 0
4883 * - Maximum Value: 4
4884 * - Default Value: 0.4
4885 * - Units: m
4886 *
4887 * \param newProximityThreshold Parameter to modify
4888 * \returns Itself
4889 */
4890 constexpr ProximityParamsConfigs &WithProximityThreshold(units::length::meter_t newProximityThreshold)
4891 {
4892 ProximityThreshold = std::move(newProximityThreshold);
4893 return *this;
4894 }
4895
4896 /**
4897 * \brief Modifies this configuration's ProximityHysteresis parameter and returns itself for
4898 * method-chaining and easier to use config API.
4899 *
4900 * How far above and below the threshold the distance needs to be to
4901 * trigger undetected and detected, respectively. This is used to
4902 * prevent bouncing between the detected and undetected states for
4903 * objects on the threshold.
4904 *
4905 * If the threshold is set to 0.1 meters, and the hysteresis is 0.01
4906 * meters, then an object needs to be within 0.09 meters to be
4907 * detected. After the object is first detected, the distance then
4908 * needs to exceed 0.11 meters to become undetected again.
4909 *
4910 * - Minimum Value: 0
4911 * - Maximum Value: 1
4912 * - Default Value: 0.01
4913 * - Units: m
4914 *
4915 * \param newProximityHysteresis Parameter to modify
4916 * \returns Itself
4917 */
4918 constexpr ProximityParamsConfigs &WithProximityHysteresis(units::length::meter_t newProximityHysteresis)
4919 {
4920 ProximityHysteresis = std::move(newProximityHysteresis);
4921 return *this;
4922 }
4923
4924 /**
4925 * \brief Modifies this configuration's MinSignalStrengthForValidMeasurement parameter and returns itself for
4926 * method-chaining and easier to use config API.
4927 *
4928 * The minimum allowable signal strength before determining the
4929 * measurement is valid.
4930 *
4931 * If the signal strength is particularly low, this typically means
4932 * the object is far away and there's fewer total samples to derive
4933 * the distance from. Set this value to be below the lowest strength
4934 * you see when you're detecting an object with the CANrange; the
4935 * default of 2500 is typically acceptable in most cases.
4936 *
4937 * - Minimum Value: 1
4938 * - Maximum Value: 15000
4939 * - Default Value: 2500
4940 * - Units:
4941 *
4942 * \param newMinSignalStrengthForValidMeasurement Parameter to modify
4943 * \returns Itself
4944 */
4945 constexpr ProximityParamsConfigs &WithMinSignalStrengthForValidMeasurement(units::dimensionless::scalar_t newMinSignalStrengthForValidMeasurement)
4946 {
4947 MinSignalStrengthForValidMeasurement = std::move(newMinSignalStrengthForValidMeasurement);
4948 return *this;
4949 }
4950
4951
4952
4953 std::string ToString() const override
4954 {
4955 std::stringstream ss;
4956 ss << "Config Group: ProximityParams" << std::endl;
4957 ss << " ProximityThreshold: " << ProximityThreshold.to<double>() << " m" << std::endl;
4958 ss << " ProximityHysteresis: " << ProximityHysteresis.to<double>() << " m" << std::endl;
4959 ss << " MinSignalStrengthForValidMeasurement: " << MinSignalStrengthForValidMeasurement.to<double>() << std::endl;
4960 return ss.str();
4961 }
4962
4963 std::string Serialize() const override
4964 {
4965 std::stringstream ss;
4966 char *ref;
4967 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityThreshold, ProximityThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4968 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityHysteresis, ProximityHysteresis.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4969 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_MinSigStrengthForValidMeas, MinSignalStrengthForValidMeasurement.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4970 return ss.str();
4971 }
4972
4973 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4974 {
4975 const char *string_c_str = to_deserialize.c_str();
4976 size_t string_length = to_deserialize.length();
4977 double ProximityThresholdVal = ProximityThreshold.to<double>();
4978 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityThreshold, string_c_str, string_length, &ProximityThresholdVal);
4979 ProximityThreshold = units::length::meter_t{ProximityThresholdVal};
4980 double ProximityHysteresisVal = ProximityHysteresis.to<double>();
4981 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityHysteresis, string_c_str, string_length, &ProximityHysteresisVal);
4982 ProximityHysteresis = units::length::meter_t{ProximityHysteresisVal};
4983 double MinSignalStrengthForValidMeasurementVal = MinSignalStrengthForValidMeasurement.to<double>();
4984 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_MinSigStrengthForValidMeas, string_c_str, string_length, &MinSignalStrengthForValidMeasurementVal);
4985 MinSignalStrengthForValidMeasurement = units::dimensionless::scalar_t{MinSignalStrengthForValidMeasurementVal};
4986 return 0;
4987 }
4988};
4989
4990
4991/**
4992 * \brief Configs that affect the ToF Field of View
4993 *
4994 * \details Includes range and center configs
4995 */
4997{
4998public:
4999 constexpr FovParamsConfigs() = default;
5000
5001 /**
5002 * \brief Specifies the target center of the Field of View in the X
5003 * direction.
5004 *
5005 * \details The exact value may be different for different CANrange
5006 * devices due to imperfections in the sensing silicon.
5007 *
5008 * - Minimum Value: -11.8
5009 * - Maximum Value: 11.8
5010 * - Default Value: 0
5011 * - Units: deg
5012 */
5013 units::angle::degree_t FOVCenterX = 0_deg;
5014 /**
5015 * \brief Specifies the target center of the Field of View in the Y
5016 * direction.
5017 *
5018 * \details The exact value may be different for different CANrange
5019 * devices due to imperfections in the sensing silicon.
5020 *
5021 * - Minimum Value: -11.8
5022 * - Maximum Value: 11.8
5023 * - Default Value: 0
5024 * - Units: deg
5025 */
5026 units::angle::degree_t FOVCenterY = 0_deg;
5027 /**
5028 * \brief Specifies the target range of the Field of View in the X
5029 * direction. This is the full range of the FOV.
5030 *
5031 * The magnitude of this is capped to abs(27 - 2*FOVCenterX).
5032 *
5033 * \details The exact value may be different for different CANrange
5034 * devices due to imperfections in the sensing silicon.
5035 *
5036 * - Minimum Value: 6.75
5037 * - Maximum Value: 27
5038 * - Default Value: 27
5039 * - Units: deg
5040 */
5041 units::angle::degree_t FOVRangeX = 27_deg;
5042 /**
5043 * \brief Specifies the target range of the Field of View in the Y
5044 * direction. This is the full range of the FOV.
5045 *
5046 * The magnitude of this is capped to abs(27 - 2*FOVCenterY).
5047 *
5048 * \details The exact value may be different for different CANrange
5049 * devices due to imperfections in the sensing silicon.
5050 *
5051 * - Minimum Value: 6.75
5052 * - Maximum Value: 27
5053 * - Default Value: 27
5054 * - Units: deg
5055 */
5056 units::angle::degree_t FOVRangeY = 27_deg;
5057
5058 /**
5059 * \brief Modifies this configuration's FOVCenterX parameter and returns itself for
5060 * method-chaining and easier to use config API.
5061 *
5062 * Specifies the target center of the Field of View in the X
5063 * direction.
5064 *
5065 * \details The exact value may be different for different CANrange
5066 * devices due to imperfections in the sensing silicon.
5067 *
5068 * - Minimum Value: -11.8
5069 * - Maximum Value: 11.8
5070 * - Default Value: 0
5071 * - Units: deg
5072 *
5073 * \param newFOVCenterX Parameter to modify
5074 * \returns Itself
5075 */
5076 constexpr FovParamsConfigs &WithFOVCenterX(units::angle::degree_t newFOVCenterX)
5077 {
5078 FOVCenterX = std::move(newFOVCenterX);
5079 return *this;
5080 }
5081
5082 /**
5083 * \brief Modifies this configuration's FOVCenterY parameter and returns itself for
5084 * method-chaining and easier to use config API.
5085 *
5086 * Specifies the target center of the Field of View in the Y
5087 * direction.
5088 *
5089 * \details The exact value may be different for different CANrange
5090 * devices due to imperfections in the sensing silicon.
5091 *
5092 * - Minimum Value: -11.8
5093 * - Maximum Value: 11.8
5094 * - Default Value: 0
5095 * - Units: deg
5096 *
5097 * \param newFOVCenterY Parameter to modify
5098 * \returns Itself
5099 */
5100 constexpr FovParamsConfigs &WithFOVCenterY(units::angle::degree_t newFOVCenterY)
5101 {
5102 FOVCenterY = std::move(newFOVCenterY);
5103 return *this;
5104 }
5105
5106 /**
5107 * \brief Modifies this configuration's FOVRangeX parameter and returns itself for
5108 * method-chaining and easier to use config API.
5109 *
5110 * Specifies the target range of the Field of View in the X direction.
5111 * This is the full range of the FOV.
5112 *
5113 * The magnitude of this is capped to abs(27 - 2*FOVCenterX).
5114 *
5115 * \details The exact value may be different for different CANrange
5116 * devices due to imperfections in the sensing silicon.
5117 *
5118 * - Minimum Value: 6.75
5119 * - Maximum Value: 27
5120 * - Default Value: 27
5121 * - Units: deg
5122 *
5123 * \param newFOVRangeX Parameter to modify
5124 * \returns Itself
5125 */
5126 constexpr FovParamsConfigs &WithFOVRangeX(units::angle::degree_t newFOVRangeX)
5127 {
5128 FOVRangeX = std::move(newFOVRangeX);
5129 return *this;
5130 }
5131
5132 /**
5133 * \brief Modifies this configuration's FOVRangeY parameter and returns itself for
5134 * method-chaining and easier to use config API.
5135 *
5136 * Specifies the target range of the Field of View in the Y direction.
5137 * This is the full range of the FOV.
5138 *
5139 * The magnitude of this is capped to abs(27 - 2*FOVCenterY).
5140 *
5141 * \details The exact value may be different for different CANrange
5142 * devices due to imperfections in the sensing silicon.
5143 *
5144 * - Minimum Value: 6.75
5145 * - Maximum Value: 27
5146 * - Default Value: 27
5147 * - Units: deg
5148 *
5149 * \param newFOVRangeY Parameter to modify
5150 * \returns Itself
5151 */
5152 constexpr FovParamsConfigs &WithFOVRangeY(units::angle::degree_t newFOVRangeY)
5153 {
5154 FOVRangeY = std::move(newFOVRangeY);
5155 return *this;
5156 }
5157
5158
5159
5160 std::string ToString() const override
5161 {
5162 std::stringstream ss;
5163 ss << "Config Group: FovParams" << std::endl;
5164 ss << " FOVCenterX: " << FOVCenterX.to<double>() << " deg" << std::endl;
5165 ss << " FOVCenterY: " << FOVCenterY.to<double>() << " deg" << std::endl;
5166 ss << " FOVRangeX: " << FOVRangeX.to<double>() << " deg" << std::endl;
5167 ss << " FOVRangeY: " << FOVRangeY.to<double>() << " deg" << std::endl;
5168 return ss.str();
5169 }
5170
5171 std::string Serialize() const override
5172 {
5173 std::stringstream ss;
5174 char *ref;
5175 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterX, FOVCenterX.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5176 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterY, FOVCenterY.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5177 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeX, FOVRangeX.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5178 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeY, FOVRangeY.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5179 return ss.str();
5180 }
5181
5182 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5183 {
5184 const char *string_c_str = to_deserialize.c_str();
5185 size_t string_length = to_deserialize.length();
5186 double FOVCenterXVal = FOVCenterX.to<double>();
5187 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterX, string_c_str, string_length, &FOVCenterXVal);
5188 FOVCenterX = units::angle::degree_t{FOVCenterXVal};
5189 double FOVCenterYVal = FOVCenterY.to<double>();
5190 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterY, string_c_str, string_length, &FOVCenterYVal);
5191 FOVCenterY = units::angle::degree_t{FOVCenterYVal};
5192 double FOVRangeXVal = FOVRangeX.to<double>();
5193 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeX, string_c_str, string_length, &FOVRangeXVal);
5194 FOVRangeX = units::angle::degree_t{FOVRangeXVal};
5195 double FOVRangeYVal = FOVRangeY.to<double>();
5196 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeY, string_c_str, string_length, &FOVRangeYVal);
5197 FOVRangeY = units::angle::degree_t{FOVRangeYVal};
5198 return 0;
5199 }
5200};
5201
5202
5203/**
5204 * \brief Configs that determine motor selection and commutation.
5205 *
5206 * \details Set these configs to match your motor setup before
5207 * commanding motor output.
5208 */
5210{
5211public:
5212 constexpr CommutationConfigs() = default;
5213
5214 /**
5215 * \brief Requires Phoenix Pro; Improves commutation and velocity
5216 * measurement for motors with hall sensors. Talon can use advanced
5217 * features to improve commutation and velocity measurement when using
5218 * a motor with hall sensors. This can improve peak efficiency by as
5219 * high as 2% and reduce noise in the measured velocity.
5220 *
5221 */
5223 /**
5224 * \brief Selects the motor and motor connections used with Talon.
5225 *
5226 * This setting determines what kind of motor and sensors are used
5227 * with the Talon. This also determines what signals are used on the
5228 * JST and Gadgeteer port.
5229 *
5230 * Motor drive will not function correctly if this setting does not
5231 * match the physical setup.
5232 *
5233 */
5235 /**
5236 * \brief If a brushed motor is selected with Motor Arrangement, this
5237 * config determines which of three leads to use.
5238 *
5239 */
5241
5242 /**
5243 * \brief Modifies this configuration's AdvancedHallSupport parameter and returns itself for
5244 * method-chaining and easier to use config API.
5245 *
5246 * Requires Phoenix Pro; Improves commutation and velocity measurement
5247 * for motors with hall sensors. Talon can use advanced features to
5248 * improve commutation and velocity measurement when using a motor
5249 * with hall sensors. This can improve peak efficiency by as high as
5250 * 2% and reduce noise in the measured velocity.
5251 *
5252 *
5253 * \param newAdvancedHallSupport Parameter to modify
5254 * \returns Itself
5255 */
5257 {
5258 AdvancedHallSupport = std::move(newAdvancedHallSupport);
5259 return *this;
5260 }
5261
5262 /**
5263 * \brief Modifies this configuration's MotorArrangement parameter and returns itself for
5264 * method-chaining and easier to use config API.
5265 *
5266 * Selects the motor and motor connections used with Talon.
5267 *
5268 * This setting determines what kind of motor and sensors are used
5269 * with the Talon. This also determines what signals are used on the
5270 * JST and Gadgeteer port.
5271 *
5272 * Motor drive will not function correctly if this setting does not
5273 * match the physical setup.
5274 *
5275 *
5276 * \param newMotorArrangement Parameter to modify
5277 * \returns Itself
5278 */
5280 {
5281 MotorArrangement = std::move(newMotorArrangement);
5282 return *this;
5283 }
5284
5285 /**
5286 * \brief Modifies this configuration's BrushedMotorWiring parameter and returns itself for
5287 * method-chaining and easier to use config API.
5288 *
5289 * If a brushed motor is selected with Motor Arrangement, this config
5290 * determines which of three leads to use.
5291 *
5292 *
5293 * \param newBrushedMotorWiring Parameter to modify
5294 * \returns Itself
5295 */
5297 {
5298 BrushedMotorWiring = std::move(newBrushedMotorWiring);
5299 return *this;
5300 }
5301
5302
5303
5304 std::string ToString() const override
5305 {
5306 std::stringstream ss;
5307 ss << "Config Group: Commutation" << std::endl;
5308 ss << " AdvancedHallSupport: " << AdvancedHallSupport << std::endl;
5309 ss << " MotorArrangement: " << MotorArrangement << std::endl;
5310 ss << " BrushedMotorWiring: " << BrushedMotorWiring << std::endl;
5311 return ss.str();
5312 }
5313
5314 std::string Serialize() const override
5315 {
5316 std::stringstream ss;
5317 char *ref;
5318 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_AdvancedHallSupport, AdvancedHallSupport.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5319 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_MotorType, MotorArrangement.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5320 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_BrushedMotorWiring, BrushedMotorWiring.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5321 return ss.str();
5322 }
5323
5324 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5325 {
5326 const char *string_c_str = to_deserialize.c_str();
5327 size_t string_length = to_deserialize.length();
5328 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_AdvancedHallSupport, string_c_str, string_length, &AdvancedHallSupport.value);
5329 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_MotorType, string_c_str, string_length, &MotorArrangement.value);
5330 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_BrushedMotorWiring, string_c_str, string_length, &BrushedMotorWiring.value);
5331 return 0;
5332 }
5333};
5334
5335
5336/**
5337 * \brief Configs related to the CANdi™ branded device's digital I/O
5338 * settings
5339 *
5340 * \details Contains float-state settings and when to assert the S1/S2
5341 * inputs.
5342 */
5344{
5345public:
5346 constexpr DigitalInputsConfigs() = default;
5347
5348 /**
5349 * \brief The floating state of the Signal 1 input (S1IN).
5350 *
5351 */
5353 /**
5354 * \brief The floating state of the Signal 2 input (S2IN).
5355 *
5356 */
5358 /**
5359 * \brief What value the Signal 1 input (S1IN) needs to be for the CTR
5360 * Electronics' CANdi™ to detect as Closed.
5361 *
5362 * \details Devices using the S1 input as a remote limit switch will
5363 * treat the switch as closed when the S1 input is this state.
5364 *
5365 */
5367 /**
5368 * \brief What value the Signal 2 input (S2IN) needs to be for the CTR
5369 * Electronics' CANdi™ to detect as Closed.
5370 *
5371 * \details Devices using the S2 input as a remote limit switch will
5372 * treat the switch as closed when the S2 input is this state.
5373 *
5374 */
5376
5377 /**
5378 * \brief Modifies this configuration's S1FloatState parameter and returns itself for
5379 * method-chaining and easier to use config API.
5380 *
5381 * The floating state of the Signal 1 input (S1IN).
5382 *
5383 *
5384 * \param newS1FloatState Parameter to modify
5385 * \returns Itself
5386 */
5388 {
5389 S1FloatState = std::move(newS1FloatState);
5390 return *this;
5391 }
5392
5393 /**
5394 * \brief Modifies this configuration's S2FloatState parameter and returns itself for
5395 * method-chaining and easier to use config API.
5396 *
5397 * The floating state of the Signal 2 input (S2IN).
5398 *
5399 *
5400 * \param newS2FloatState Parameter to modify
5401 * \returns Itself
5402 */
5404 {
5405 S2FloatState = std::move(newS2FloatState);
5406 return *this;
5407 }
5408
5409 /**
5410 * \brief Modifies this configuration's S1CloseState parameter and returns itself for
5411 * method-chaining and easier to use config API.
5412 *
5413 * What value the Signal 1 input (S1IN) needs to be for the CTR
5414 * Electronics' CANdi™ to detect as Closed.
5415 *
5416 * \details Devices using the S1 input as a remote limit switch will
5417 * treat the switch as closed when the S1 input is this state.
5418 *
5419 *
5420 * \param newS1CloseState Parameter to modify
5421 * \returns Itself
5422 */
5424 {
5425 S1CloseState = std::move(newS1CloseState);
5426 return *this;
5427 }
5428
5429 /**
5430 * \brief Modifies this configuration's S2CloseState parameter and returns itself for
5431 * method-chaining and easier to use config API.
5432 *
5433 * What value the Signal 2 input (S2IN) needs to be for the CTR
5434 * Electronics' CANdi™ to detect as Closed.
5435 *
5436 * \details Devices using the S2 input as a remote limit switch will
5437 * treat the switch as closed when the S2 input is this state.
5438 *
5439 *
5440 * \param newS2CloseState Parameter to modify
5441 * \returns Itself
5442 */
5444 {
5445 S2CloseState = std::move(newS2CloseState);
5446 return *this;
5447 }
5448
5449
5450
5451 std::string ToString() const override
5452 {
5453 std::stringstream ss;
5454 ss << "Config Group: DigitalInputs" << std::endl;
5455 ss << " S1FloatState: " << S1FloatState << std::endl;
5456 ss << " S2FloatState: " << S2FloatState << std::endl;
5457 ss << " S1CloseState: " << S1CloseState << std::endl;
5458 ss << " S2CloseState: " << S2CloseState << std::endl;
5459 return ss.str();
5460 }
5461
5462 std::string Serialize() const override
5463 {
5464 std::stringstream ss;
5465 char *ref;
5466 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S1FloatState, S1FloatState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5467 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S2FloatState, S2FloatState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5468 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_S1_CloseState, S1CloseState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5469 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_S2_CloseState, S2CloseState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5470 return ss.str();
5471 }
5472
5473 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5474 {
5475 const char *string_c_str = to_deserialize.c_str();
5476 size_t string_length = to_deserialize.length();
5477 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S1FloatState, string_c_str, string_length, &S1FloatState.value);
5478 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S2FloatState, string_c_str, string_length, &S2FloatState.value);
5479 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_S1_CloseState, string_c_str, string_length, &S1CloseState.value);
5480 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_S2_CloseState, string_c_str, string_length, &S2CloseState.value);
5481 return 0;
5482 }
5483};
5484
5485
5486/**
5487 * \brief Configs related to the CANdi™ branded device's quadrature
5488 * interface using both the S1IN and S2IN inputs
5489 *
5490 * \details All the configs related to the quadrature interface for
5491 * the CANdi™ branded device , including encoder edges per
5492 * revolution and sensor direction.
5493 */
5495{
5496public:
5497 constexpr QuadratureConfigs() = default;
5498
5499 /**
5500 * \brief The number of quadrature edges in one rotation for the
5501 * quadrature sensor connected to the Talon data port.
5502 *
5503 * This is the total number of transitions from high-to-low or
5504 * low-to-high across both channels per rotation of the sensor. This
5505 * is also equivalent to the Counts Per Revolution when using 4x
5506 * decoding.
5507 *
5508 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
5509 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
5510 * 4096 edges per rotation.
5511 *
5512 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
5513 * RPM.
5514 *
5515 * - Minimum Value: 1
5516 * - Maximum Value: 1000000
5517 * - Default Value: 4096
5518 * - Units:
5519 */
5521 /**
5522 * \brief Direction of the quadrature sensor to determine positive
5523 * rotation. Invert this so that forward motion on the mechanism
5524 * results in an increase in quadrature position.
5525 *
5526 * - Default Value: False
5527 */
5528 bool SensorDirection = false;
5529
5530 /**
5531 * \brief Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for
5532 * method-chaining and easier to use config API.
5533 *
5534 * The number of quadrature edges in one rotation for the quadrature
5535 * sensor connected to the Talon data port.
5536 *
5537 * This is the total number of transitions from high-to-low or
5538 * low-to-high across both channels per rotation of the sensor. This
5539 * is also equivalent to the Counts Per Revolution when using 4x
5540 * decoding.
5541 *
5542 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
5543 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
5544 * 4096 edges per rotation.
5545 *
5546 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
5547 * RPM.
5548 *
5549 * - Minimum Value: 1
5550 * - Maximum Value: 1000000
5551 * - Default Value: 4096
5552 * - Units:
5553 *
5554 * \param newQuadratureEdgesPerRotation Parameter to modify
5555 * \returns Itself
5556 */
5557 constexpr QuadratureConfigs &WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
5558 {
5559 QuadratureEdgesPerRotation = std::move(newQuadratureEdgesPerRotation);
5560 return *this;
5561 }
5562
5563 /**
5564 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5565 * method-chaining and easier to use config API.
5566 *
5567 * Direction of the quadrature sensor to determine positive rotation.
5568 * Invert this so that forward motion on the mechanism results in an
5569 * increase in quadrature position.
5570 *
5571 * - Default Value: False
5572 *
5573 * \param newSensorDirection Parameter to modify
5574 * \returns Itself
5575 */
5576 constexpr QuadratureConfigs &WithSensorDirection(bool newSensorDirection)
5577 {
5578 SensorDirection = std::move(newSensorDirection);
5579 return *this;
5580 }
5581
5582
5583
5584 std::string ToString() const override
5585 {
5586 std::stringstream ss;
5587 ss << "Config Group: Quadrature" << std::endl;
5588 ss << " QuadratureEdgesPerRotation: " << QuadratureEdgesPerRotation << std::endl;
5589 ss << " SensorDirection: " << SensorDirection << std::endl;
5590 return ss.str();
5591 }
5592
5593 std::string Serialize() const override
5594 {
5595 std::stringstream ss;
5596 char *ref;
5597 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, QuadratureEdgesPerRotation, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5598 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_Quad_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5599 return ss.str();
5600 }
5601
5602 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5603 {
5604 const char *string_c_str = to_deserialize.c_str();
5605 size_t string_length = to_deserialize.length();
5606 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, string_c_str, string_length, &QuadratureEdgesPerRotation);
5607 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_Quad_SensorDirection, string_c_str, string_length, &SensorDirection);
5608 return 0;
5609 }
5610};
5611
5612
5613/**
5614 * \brief Configs related to the CANdi™ branded device's PWM interface
5615 * on the Signal 1 input (S1IN)
5616 *
5617 * \details All the configs related to the PWM interface for the
5618 * CANdi™ branded device on S1, including absolute sensor
5619 * offset, absolute sensor discontinuity point and sensor
5620 * direction.
5621 */
5623{
5624public:
5625 constexpr PWM1Configs() = default;
5626
5627 /**
5628 * \brief The offset applied to the PWM sensor.
5629 *
5630 * This can be used to zero the sensor position in applications where
5631 * the sensor is 1:1 with the mechanism.
5632 *
5633 * - Minimum Value: -1
5634 * - Maximum Value: 1
5635 * - Default Value: 0.0
5636 * - Units: rotations
5637 */
5638 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
5639 /**
5640 * \brief The positive discontinuity point of the absolute sensor in
5641 * rotations. This determines the point at which the absolute sensor
5642 * wraps around, keeping the absolute position in the range [x-1, x).
5643 *
5644 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5645 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5646 * 0.5)
5647 * - Setting this to 0 makes the absolute position always negative
5648 * [-1, 0)
5649 *
5650 * Many rotational mechanisms such as arms have a region of motion
5651 * that is unreachable. This should be set to the center of that
5652 * region of motion, in non-negative rotations. This affects the
5653 * position of the device at bootup.
5654 *
5655 * \details For example, consider an arm which can travel from -0.2 to
5656 * 0.6 rotations with a little leeway, where 0 is horizontally
5657 * forward. Since -0.2 rotations has the same absolute position as 0.8
5658 * rotations, we can say that the arm typically does not travel in the
5659 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5660 * would be the center of that range, which is 0.7 rotations. This
5661 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5662 *
5663 * On a Talon motor controller, this is only supported when using the
5664 * PulseWidth sensor source.
5665 *
5666 * - Minimum Value: 0.0
5667 * - Maximum Value: 1.0
5668 * - Default Value: 0.5
5669 * - Units: rotations
5670 */
5671 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
5672 /**
5673 * \brief Direction of the PWM sensor to determine positive rotation.
5674 * Invert this so that forward motion on the mechanism results in an
5675 * increase in PWM position.
5676 *
5677 * - Default Value: False
5678 */
5679 bool SensorDirection = false;
5680
5681 /**
5682 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
5683 * method-chaining and easier to use config API.
5684 *
5685 * The offset applied to the PWM sensor.
5686 *
5687 * This can be used to zero the sensor position in applications where
5688 * the sensor is 1:1 with the mechanism.
5689 *
5690 * - Minimum Value: -1
5691 * - Maximum Value: 1
5692 * - Default Value: 0.0
5693 * - Units: rotations
5694 *
5695 * \param newAbsoluteSensorOffset Parameter to modify
5696 * \returns Itself
5697 */
5698 constexpr PWM1Configs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
5699 {
5700 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
5701 return *this;
5702 }
5703
5704 /**
5705 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
5706 * method-chaining and easier to use config API.
5707 *
5708 * The positive discontinuity point of the absolute sensor in
5709 * rotations. This determines the point at which the absolute sensor
5710 * wraps around, keeping the absolute position in the range [x-1, x).
5711 *
5712 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5713 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5714 * 0.5)
5715 * - Setting this to 0 makes the absolute position always negative
5716 * [-1, 0)
5717 *
5718 * Many rotational mechanisms such as arms have a region of motion
5719 * that is unreachable. This should be set to the center of that
5720 * region of motion, in non-negative rotations. This affects the
5721 * position of the device at bootup.
5722 *
5723 * \details For example, consider an arm which can travel from -0.2 to
5724 * 0.6 rotations with a little leeway, where 0 is horizontally
5725 * forward. Since -0.2 rotations has the same absolute position as 0.8
5726 * rotations, we can say that the arm typically does not travel in the
5727 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5728 * would be the center of that range, which is 0.7 rotations. This
5729 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5730 *
5731 * On a Talon motor controller, this is only supported when using the
5732 * PulseWidth sensor source.
5733 *
5734 * - Minimum Value: 0.0
5735 * - Maximum Value: 1.0
5736 * - Default Value: 0.5
5737 * - Units: rotations
5738 *
5739 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
5740 * \returns Itself
5741 */
5742 constexpr PWM1Configs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
5743 {
5744 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
5745 return *this;
5746 }
5747
5748 /**
5749 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5750 * method-chaining and easier to use config API.
5751 *
5752 * Direction of the PWM sensor to determine positive rotation. Invert
5753 * this so that forward motion on the mechanism results in an increase
5754 * in PWM position.
5755 *
5756 * - Default Value: False
5757 *
5758 * \param newSensorDirection Parameter to modify
5759 * \returns Itself
5760 */
5761 constexpr PWM1Configs &WithSensorDirection(bool newSensorDirection)
5762 {
5763 SensorDirection = std::move(newSensorDirection);
5764 return *this;
5765 }
5766
5767
5768
5769 std::string ToString() const override
5770 {
5771 std::stringstream ss;
5772 ss << "Config Group: PWM1" << std::endl;
5773 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
5774 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
5775 ss << " SensorDirection: " << SensorDirection << std::endl;
5776 return ss.str();
5777 }
5778
5779 std::string Serialize() const override
5780 {
5781 std::stringstream ss;
5782 char *ref;
5783 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5784 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5785 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM1_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5786 return ss.str();
5787 }
5788
5789 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5790 {
5791 const char *string_c_str = to_deserialize.c_str();
5792 size_t string_length = to_deserialize.length();
5793 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
5794 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
5795 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
5796 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
5797 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
5798 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
5799 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM1_SensorDirection, string_c_str, string_length, &SensorDirection);
5800 return 0;
5801 }
5802};
5803
5804
5805/**
5806 * \brief Configs related to the CANdi™ branded device's PWM interface
5807 * on the Signal 2 input (S2IN)
5808 *
5809 * \details All the configs related to the PWM interface for the
5810 * CANdi™ branded device on S1, including absolute sensor
5811 * offset, absolute sensor discontinuity point and sensor
5812 * direction.
5813 */
5815{
5816public:
5817 constexpr PWM2Configs() = default;
5818
5819 /**
5820 * \brief The offset applied to the PWM sensor.
5821 *
5822 * This can be used to zero the sensor position in applications where
5823 * the sensor is 1:1 with the mechanism.
5824 *
5825 * - Minimum Value: -1
5826 * - Maximum Value: 1
5827 * - Default Value: 0.0
5828 * - Units: rotations
5829 */
5830 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
5831 /**
5832 * \brief The positive discontinuity point of the absolute sensor in
5833 * rotations. This determines the point at which the absolute sensor
5834 * wraps around, keeping the absolute position in the range [x-1, x).
5835 *
5836 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5837 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5838 * 0.5)
5839 * - Setting this to 0 makes the absolute position always negative
5840 * [-1, 0)
5841 *
5842 * Many rotational mechanisms such as arms have a region of motion
5843 * that is unreachable. This should be set to the center of that
5844 * region of motion, in non-negative rotations. This affects the
5845 * position of the device at bootup.
5846 *
5847 * \details For example, consider an arm which can travel from -0.2 to
5848 * 0.6 rotations with a little leeway, where 0 is horizontally
5849 * forward. Since -0.2 rotations has the same absolute position as 0.8
5850 * rotations, we can say that the arm typically does not travel in the
5851 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5852 * would be the center of that range, which is 0.7 rotations. This
5853 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5854 *
5855 * On a Talon motor controller, this is only supported when using the
5856 * PulseWidth sensor source.
5857 *
5858 * - Minimum Value: 0.0
5859 * - Maximum Value: 1.0
5860 * - Default Value: 0.5
5861 * - Units: rotations
5862 */
5863 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
5864 /**
5865 * \brief Direction of the PWM sensor to determine positive rotation.
5866 * Invert this so that forward motion on the mechanism results in an
5867 * increase in PWM position.
5868 *
5869 * - Default Value: False
5870 */
5871 bool SensorDirection = false;
5872
5873 /**
5874 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
5875 * method-chaining and easier to use config API.
5876 *
5877 * The offset applied to the PWM sensor.
5878 *
5879 * This can be used to zero the sensor position in applications where
5880 * the sensor is 1:1 with the mechanism.
5881 *
5882 * - Minimum Value: -1
5883 * - Maximum Value: 1
5884 * - Default Value: 0.0
5885 * - Units: rotations
5886 *
5887 * \param newAbsoluteSensorOffset Parameter to modify
5888 * \returns Itself
5889 */
5890 constexpr PWM2Configs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
5891 {
5892 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
5893 return *this;
5894 }
5895
5896 /**
5897 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
5898 * method-chaining and easier to use config API.
5899 *
5900 * The positive discontinuity point of the absolute sensor in
5901 * rotations. This determines the point at which the absolute sensor
5902 * wraps around, keeping the absolute position in the range [x-1, x).
5903 *
5904 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5905 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5906 * 0.5)
5907 * - Setting this to 0 makes the absolute position always negative
5908 * [-1, 0)
5909 *
5910 * Many rotational mechanisms such as arms have a region of motion
5911 * that is unreachable. This should be set to the center of that
5912 * region of motion, in non-negative rotations. This affects the
5913 * position of the device at bootup.
5914 *
5915 * \details For example, consider an arm which can travel from -0.2 to
5916 * 0.6 rotations with a little leeway, where 0 is horizontally
5917 * forward. Since -0.2 rotations has the same absolute position as 0.8
5918 * rotations, we can say that the arm typically does not travel in the
5919 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5920 * would be the center of that range, which is 0.7 rotations. This
5921 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5922 *
5923 * On a Talon motor controller, this is only supported when using the
5924 * PulseWidth sensor source.
5925 *
5926 * - Minimum Value: 0.0
5927 * - Maximum Value: 1.0
5928 * - Default Value: 0.5
5929 * - Units: rotations
5930 *
5931 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
5932 * \returns Itself
5933 */
5934 constexpr PWM2Configs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
5935 {
5936 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
5937 return *this;
5938 }
5939
5940 /**
5941 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5942 * method-chaining and easier to use config API.
5943 *
5944 * Direction of the PWM sensor to determine positive rotation. Invert
5945 * this so that forward motion on the mechanism results in an increase
5946 * in PWM position.
5947 *
5948 * - Default Value: False
5949 *
5950 * \param newSensorDirection Parameter to modify
5951 * \returns Itself
5952 */
5953 constexpr PWM2Configs &WithSensorDirection(bool newSensorDirection)
5954 {
5955 SensorDirection = std::move(newSensorDirection);
5956 return *this;
5957 }
5958
5959
5960
5961 std::string ToString() const override
5962 {
5963 std::stringstream ss;
5964 ss << "Config Group: PWM2" << std::endl;
5965 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
5966 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
5967 ss << " SensorDirection: " << SensorDirection << std::endl;
5968 return ss.str();
5969 }
5970
5971 std::string Serialize() const override
5972 {
5973 std::stringstream ss;
5974 char *ref;
5975 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5976 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5977 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM2_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5978 return ss.str();
5979 }
5980
5981 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5982 {
5983 const char *string_c_str = to_deserialize.c_str();
5984 size_t string_length = to_deserialize.length();
5985 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
5986 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
5987 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
5988 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
5989 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
5990 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
5991 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM2_SensorDirection, string_c_str, string_length, &SensorDirection);
5992 return 0;
5993 }
5994};
5995
5996
5997/**
5998 * \brief Gains for the specified slot.
5999 *
6000 * \details If this slot is selected, these gains are used in closed
6001 * loop control requests.
6002 */
6004{
6005public:
6006 constexpr Slot0Configs() = default;
6007
6008 /**
6009 * \brief Proportional Gain.
6010 *
6011 * \details The units for this gain is dependent on the control mode.
6012 * Since this gain is multiplied by error in the input, the units
6013 * should be defined as units of output per unit of input error. For
6014 * example, when controlling velocity using a duty cycle closed loop,
6015 * the units for the proportional gain will be duty cycle per rps of
6016 * error, or 1/rps.
6017 *
6018 * - Minimum Value: 0
6019 * - Maximum Value: 3.4e+38
6020 * - Default Value: 0
6021 * - Units:
6022 */
6023 units::dimensionless::scalar_t kP = 0;
6024 /**
6025 * \brief Integral Gain.
6026 *
6027 * \details The units for this gain is dependent on the control mode.
6028 * Since this gain is multiplied by error in the input integrated over
6029 * time (in units of seconds), the units should be defined as units of
6030 * output per unit of integrated input error. For example, when
6031 * controlling velocity using a duty cycle closed loop, integrating
6032 * velocity over time results in rps * s = rotations. Therefore, the
6033 * units for the integral gain will be duty cycle per rotation of
6034 * accumulated error, or 1/rot.
6035 *
6036 * - Minimum Value: 0
6037 * - Maximum Value: 3.4e+38
6038 * - Default Value: 0
6039 * - Units:
6040 */
6041 units::dimensionless::scalar_t kI = 0;
6042 /**
6043 * \brief Derivative Gain.
6044 *
6045 * \details The units for this gain is dependent on the control mode.
6046 * Since this gain is multiplied by the derivative of error in the
6047 * input with respect to time (in units of seconds), the units should
6048 * be defined as units of output per unit of the differentiated input
6049 * error. For example, when controlling velocity using a duty cycle
6050 * closed loop, the derivative of velocity with respect to time is rot
6051 * per sec², which is acceleration. Therefore, the units for the
6052 * derivative gain will be duty cycle per unit of acceleration error,
6053 * or 1/(rot per sec²).
6054 *
6055 * - Minimum Value: 0
6056 * - Maximum Value: 3.4e+38
6057 * - Default Value: 0
6058 * - Units:
6059 */
6060 units::dimensionless::scalar_t kD = 0;
6061 /**
6062 * \brief Static Feedforward Gain.
6063 *
6064 * \details This is added to the closed loop output. The unit for this
6065 * constant is dependent on the control mode, typically fractional
6066 * duty cycle, voltage, or torque current.
6067 *
6068 * The sign is typically determined by reference velocity when using
6069 * position, velocity, and Motion Magic® closed loop modes. However,
6070 * when using position closed loop with zero velocity reference (no
6071 * motion profiling), the application can instead use the position
6072 * closed loop error by setting the Static Feedforward Sign
6073 * configuration parameter. When doing so, we recommend the minimal
6074 * amount of kS, otherwise the motor output may dither when closed
6075 * loop error is near zero.
6076 *
6077 * - Minimum Value: -512
6078 * - Maximum Value: 511
6079 * - Default Value: 0
6080 * - Units:
6081 */
6082 units::dimensionless::scalar_t kS = 0;
6083 /**
6084 * \brief Velocity Feedforward Gain.
6085 *
6086 * \details The units for this gain is dependent on the control mode.
6087 * Since this gain is multiplied by the requested velocity, the units
6088 * should be defined as units of output per unit of requested input
6089 * velocity. For example, when controlling velocity using a duty cycle
6090 * closed loop, the units for the velocity feedfoward gain will be
6091 * duty cycle per requested rps, or 1/rps.
6092 *
6093 * - Minimum Value: 0
6094 * - Maximum Value: 3.4e+38
6095 * - Default Value: 0
6096 * - Units:
6097 */
6098 units::dimensionless::scalar_t kV = 0;
6099 /**
6100 * \brief Acceleration Feedforward Gain.
6101 *
6102 * \details The units for this gain is dependent on the control mode.
6103 * Since this gain is multiplied by the requested acceleration, the
6104 * units should be defined as units of output per unit of requested
6105 * input acceleration. For example, when controlling velocity using a
6106 * duty cycle closed loop, the units for the acceleration feedfoward
6107 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6108 * sec²).
6109 *
6110 * - Minimum Value: 0
6111 * - Maximum Value: 3.4e+38
6112 * - Default Value: 0
6113 * - Units:
6114 */
6115 units::dimensionless::scalar_t kA = 0;
6116 /**
6117 * \brief Gravity Feedforward/Feedback Gain.
6118 *
6119 * \details This is added to the closed loop output. The sign is
6120 * determined by GravityType. The unit for this constant is dependent
6121 * on the control mode, typically fractional duty cycle, voltage, or
6122 * torque current.
6123 *
6124 * - Minimum Value: -512
6125 * - Maximum Value: 511
6126 * - Default Value: 0
6127 * - Units:
6128 */
6129 units::dimensionless::scalar_t kG = 0;
6130 /**
6131 * \brief Gravity Feedforward/Feedback Type.
6132 *
6133 * This determines the type of the gravity feedforward/feedback.
6134 *
6135 * Choose Elevator_Static for systems where the gravity feedforward is
6136 * constant, such as an elevator. The gravity feedforward output will
6137 * always have the same sign.
6138 *
6139 * Choose Arm_Cosine for systems where the gravity feedback is
6140 * dependent on the angular position of the mechanism, such as an arm.
6141 * The gravity feedback output will vary depending on the mechanism
6142 * angular position. Note that the sensor offset and ratios must be
6143 * configured so that the sensor reports a position of 0 when the
6144 * mechanism is horizonal (parallel to the ground), and the reported
6145 * sensor position is 1:1 with the mechanism.
6146 *
6147 */
6149 /**
6150 * \brief Static Feedforward Sign during position closed loop.
6151 *
6152 * This determines the sign of the applied kS during position
6153 * closed-loop modes. The default behavior uses the velocity reference
6154 * sign. This works well with velocity closed loop, Motion Magic®
6155 * controls, and position closed loop when velocity reference is
6156 * specified (motion profiling).
6157 *
6158 * However, when using position closed loop with zero velocity
6159 * reference (no motion profiling), the application may want to apply
6160 * static feedforward based on the sign of closed loop error instead.
6161 * When doing so, we recommend using the minimal amount of kS,
6162 * otherwise the motor output may dither when closed loop error is
6163 * near zero.
6164 *
6165 */
6167
6168 /**
6169 * \brief Modifies this configuration's kP parameter and returns itself for
6170 * method-chaining and easier to use config API.
6171 *
6172 * Proportional Gain.
6173 *
6174 * \details The units for this gain is dependent on the control mode.
6175 * Since this gain is multiplied by error in the input, the units
6176 * should be defined as units of output per unit of input error. For
6177 * example, when controlling velocity using a duty cycle closed loop,
6178 * the units for the proportional gain will be duty cycle per rps of
6179 * error, or 1/rps.
6180 *
6181 * - Minimum Value: 0
6182 * - Maximum Value: 3.4e+38
6183 * - Default Value: 0
6184 * - Units:
6185 *
6186 * \param newKP Parameter to modify
6187 * \returns Itself
6188 */
6189 constexpr Slot0Configs &WithKP(units::dimensionless::scalar_t newKP)
6190 {
6191 kP = std::move(newKP);
6192 return *this;
6193 }
6194
6195 /**
6196 * \brief Modifies this configuration's kI parameter and returns itself for
6197 * method-chaining and easier to use config API.
6198 *
6199 * Integral Gain.
6200 *
6201 * \details The units for this gain is dependent on the control mode.
6202 * Since this gain is multiplied by error in the input integrated over
6203 * time (in units of seconds), the units should be defined as units of
6204 * output per unit of integrated input error. For example, when
6205 * controlling velocity using a duty cycle closed loop, integrating
6206 * velocity over time results in rps * s = rotations. Therefore, the
6207 * units for the integral gain will be duty cycle per rotation of
6208 * accumulated error, or 1/rot.
6209 *
6210 * - Minimum Value: 0
6211 * - Maximum Value: 3.4e+38
6212 * - Default Value: 0
6213 * - Units:
6214 *
6215 * \param newKI Parameter to modify
6216 * \returns Itself
6217 */
6218 constexpr Slot0Configs &WithKI(units::dimensionless::scalar_t newKI)
6219 {
6220 kI = std::move(newKI);
6221 return *this;
6222 }
6223
6224 /**
6225 * \brief Modifies this configuration's kD parameter and returns itself for
6226 * method-chaining and easier to use config API.
6227 *
6228 * Derivative Gain.
6229 *
6230 * \details The units for this gain is dependent on the control mode.
6231 * Since this gain is multiplied by the derivative of error in the
6232 * input with respect to time (in units of seconds), the units should
6233 * be defined as units of output per unit of the differentiated input
6234 * error. For example, when controlling velocity using a duty cycle
6235 * closed loop, the derivative of velocity with respect to time is rot
6236 * per sec², which is acceleration. Therefore, the units for the
6237 * derivative gain will be duty cycle per unit of acceleration error,
6238 * or 1/(rot per sec²).
6239 *
6240 * - Minimum Value: 0
6241 * - Maximum Value: 3.4e+38
6242 * - Default Value: 0
6243 * - Units:
6244 *
6245 * \param newKD Parameter to modify
6246 * \returns Itself
6247 */
6248 constexpr Slot0Configs &WithKD(units::dimensionless::scalar_t newKD)
6249 {
6250 kD = std::move(newKD);
6251 return *this;
6252 }
6253
6254 /**
6255 * \brief Modifies this configuration's kS parameter and returns itself for
6256 * method-chaining and easier to use config API.
6257 *
6258 * Static Feedforward Gain.
6259 *
6260 * \details This is added to the closed loop output. The unit for this
6261 * constant is dependent on the control mode, typically fractional
6262 * duty cycle, voltage, or torque current.
6263 *
6264 * The sign is typically determined by reference velocity when using
6265 * position, velocity, and Motion Magic® closed loop modes. However,
6266 * when using position closed loop with zero velocity reference (no
6267 * motion profiling), the application can instead use the position
6268 * closed loop error by setting the Static Feedforward Sign
6269 * configuration parameter. When doing so, we recommend the minimal
6270 * amount of kS, otherwise the motor output may dither when closed
6271 * loop error is near zero.
6272 *
6273 * - Minimum Value: -512
6274 * - Maximum Value: 511
6275 * - Default Value: 0
6276 * - Units:
6277 *
6278 * \param newKS Parameter to modify
6279 * \returns Itself
6280 */
6281 constexpr Slot0Configs &WithKS(units::dimensionless::scalar_t newKS)
6282 {
6283 kS = std::move(newKS);
6284 return *this;
6285 }
6286
6287 /**
6288 * \brief Modifies this configuration's kV parameter and returns itself for
6289 * method-chaining and easier to use config API.
6290 *
6291 * Velocity Feedforward Gain.
6292 *
6293 * \details The units for this gain is dependent on the control mode.
6294 * Since this gain is multiplied by the requested velocity, the units
6295 * should be defined as units of output per unit of requested input
6296 * velocity. For example, when controlling velocity using a duty cycle
6297 * closed loop, the units for the velocity feedfoward gain will be
6298 * duty cycle per requested rps, or 1/rps.
6299 *
6300 * - Minimum Value: 0
6301 * - Maximum Value: 3.4e+38
6302 * - Default Value: 0
6303 * - Units:
6304 *
6305 * \param newKV Parameter to modify
6306 * \returns Itself
6307 */
6308 constexpr Slot0Configs &WithKV(units::dimensionless::scalar_t newKV)
6309 {
6310 kV = std::move(newKV);
6311 return *this;
6312 }
6313
6314 /**
6315 * \brief Modifies this configuration's kA parameter and returns itself for
6316 * method-chaining and easier to use config API.
6317 *
6318 * Acceleration Feedforward Gain.
6319 *
6320 * \details The units for this gain is dependent on the control mode.
6321 * Since this gain is multiplied by the requested acceleration, the
6322 * units should be defined as units of output per unit of requested
6323 * input acceleration. For example, when controlling velocity using a
6324 * duty cycle closed loop, the units for the acceleration feedfoward
6325 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6326 * sec²).
6327 *
6328 * - Minimum Value: 0
6329 * - Maximum Value: 3.4e+38
6330 * - Default Value: 0
6331 * - Units:
6332 *
6333 * \param newKA Parameter to modify
6334 * \returns Itself
6335 */
6336 constexpr Slot0Configs &WithKA(units::dimensionless::scalar_t newKA)
6337 {
6338 kA = std::move(newKA);
6339 return *this;
6340 }
6341
6342 /**
6343 * \brief Modifies this configuration's kG parameter and returns itself for
6344 * method-chaining and easier to use config API.
6345 *
6346 * Gravity Feedforward/Feedback Gain.
6347 *
6348 * \details This is added to the closed loop output. The sign is
6349 * determined by GravityType. The unit for this constant is dependent
6350 * on the control mode, typically fractional duty cycle, voltage, or
6351 * torque current.
6352 *
6353 * - Minimum Value: -512
6354 * - Maximum Value: 511
6355 * - Default Value: 0
6356 * - Units:
6357 *
6358 * \param newKG Parameter to modify
6359 * \returns Itself
6360 */
6361 constexpr Slot0Configs &WithKG(units::dimensionless::scalar_t newKG)
6362 {
6363 kG = std::move(newKG);
6364 return *this;
6365 }
6366
6367 /**
6368 * \brief Modifies this configuration's GravityType parameter and returns itself for
6369 * method-chaining and easier to use config API.
6370 *
6371 * Gravity Feedforward/Feedback Type.
6372 *
6373 * This determines the type of the gravity feedforward/feedback.
6374 *
6375 * Choose Elevator_Static for systems where the gravity feedforward is
6376 * constant, such as an elevator. The gravity feedforward output will
6377 * always have the same sign.
6378 *
6379 * Choose Arm_Cosine for systems where the gravity feedback is
6380 * dependent on the angular position of the mechanism, such as an arm.
6381 * The gravity feedback output will vary depending on the mechanism
6382 * angular position. Note that the sensor offset and ratios must be
6383 * configured so that the sensor reports a position of 0 when the
6384 * mechanism is horizonal (parallel to the ground), and the reported
6385 * sensor position is 1:1 with the mechanism.
6386 *
6387 *
6388 * \param newGravityType Parameter to modify
6389 * \returns Itself
6390 */
6392 {
6393 GravityType = std::move(newGravityType);
6394 return *this;
6395 }
6396
6397 /**
6398 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
6399 * method-chaining and easier to use config API.
6400 *
6401 * Static Feedforward Sign during position closed loop.
6402 *
6403 * This determines the sign of the applied kS during position
6404 * closed-loop modes. The default behavior uses the velocity reference
6405 * sign. This works well with velocity closed loop, Motion Magic®
6406 * controls, and position closed loop when velocity reference is
6407 * specified (motion profiling).
6408 *
6409 * However, when using position closed loop with zero velocity
6410 * reference (no motion profiling), the application may want to apply
6411 * static feedforward based on the sign of closed loop error instead.
6412 * When doing so, we recommend using the minimal amount of kS,
6413 * otherwise the motor output may dither when closed loop error is
6414 * near zero.
6415 *
6416 *
6417 * \param newStaticFeedforwardSign Parameter to modify
6418 * \returns Itself
6419 */
6421 {
6422 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
6423 return *this;
6424 }
6425
6426 static Slot0Configs From(const SlotConfigs &value);
6427
6428 std::string ToString() const override
6429 {
6430 std::stringstream ss;
6431 ss << "Config Group: Slot0" << std::endl;
6432 ss << " kP: " << kP.to<double>() << std::endl;
6433 ss << " kI: " << kI.to<double>() << std::endl;
6434 ss << " kD: " << kD.to<double>() << std::endl;
6435 ss << " kS: " << kS.to<double>() << std::endl;
6436 ss << " kV: " << kV.to<double>() << std::endl;
6437 ss << " kA: " << kA.to<double>() << std::endl;
6438 ss << " kG: " << kG.to<double>() << std::endl;
6439 ss << " GravityType: " << GravityType << std::endl;
6440 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
6441 return ss.str();
6442 }
6443
6444 std::string Serialize() const override
6445 {
6446 std::stringstream ss;
6447 char *ref;
6448 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6449 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6450 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6451 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6452 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6453 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6454 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6455 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6456 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6457 return ss.str();
6458 }
6459
6460 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
6461 {
6462 const char *string_c_str = to_deserialize.c_str();
6463 size_t string_length = to_deserialize.length();
6464 double kPVal = kP.to<double>();
6465 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kP, string_c_str, string_length, &kPVal);
6466 kP = units::dimensionless::scalar_t{kPVal};
6467 double kIVal = kI.to<double>();
6468 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kI, string_c_str, string_length, &kIVal);
6469 kI = units::dimensionless::scalar_t{kIVal};
6470 double kDVal = kD.to<double>();
6471 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kD, string_c_str, string_length, &kDVal);
6472 kD = units::dimensionless::scalar_t{kDVal};
6473 double kSVal = kS.to<double>();
6474 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kS, string_c_str, string_length, &kSVal);
6475 kS = units::dimensionless::scalar_t{kSVal};
6476 double kVVal = kV.to<double>();
6477 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kV, string_c_str, string_length, &kVVal);
6478 kV = units::dimensionless::scalar_t{kVVal};
6479 double kAVal = kA.to<double>();
6480 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kA, string_c_str, string_length, &kAVal);
6481 kA = units::dimensionless::scalar_t{kAVal};
6482 double kGVal = kG.to<double>();
6483 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kG, string_c_str, string_length, &kGVal);
6484 kG = units::dimensionless::scalar_t{kGVal};
6485 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kG_Type, string_c_str, string_length, &GravityType.value);
6486 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
6487 return 0;
6488 }
6489};
6490
6491
6492/**
6493 * \brief Gains for the specified slot.
6494 *
6495 * \details If this slot is selected, these gains are used in closed
6496 * loop control requests.
6497 */
6499{
6500public:
6501 constexpr Slot1Configs() = default;
6502
6503 /**
6504 * \brief Proportional Gain.
6505 *
6506 * \details The units for this gain is dependent on the control mode.
6507 * Since this gain is multiplied by error in the input, the units
6508 * should be defined as units of output per unit of input error. For
6509 * example, when controlling velocity using a duty cycle closed loop,
6510 * the units for the proportional gain will be duty cycle per rps, or
6511 * 1/rps.
6512 *
6513 * - Minimum Value: 0
6514 * - Maximum Value: 3.4e+38
6515 * - Default Value: 0
6516 * - Units:
6517 */
6518 units::dimensionless::scalar_t kP = 0;
6519 /**
6520 * \brief Integral Gain.
6521 *
6522 * \details The units for this gain is dependent on the control mode.
6523 * Since this gain is multiplied by error in the input integrated over
6524 * time (in units of seconds), the units should be defined as units of
6525 * output per unit of integrated input error. For example, when
6526 * controlling velocity using a duty cycle closed loop, integrating
6527 * velocity over time results in rps * s = rotations. Therefore, the
6528 * units for the integral gain will be duty cycle per rotation of
6529 * accumulated error, or 1/rot.
6530 *
6531 * - Minimum Value: 0
6532 * - Maximum Value: 3.4e+38
6533 * - Default Value: 0
6534 * - Units:
6535 */
6536 units::dimensionless::scalar_t kI = 0;
6537 /**
6538 * \brief Derivative Gain.
6539 *
6540 * \details The units for this gain is dependent on the control mode.
6541 * Since this gain is multiplied by the derivative of error in the
6542 * input with respect to time (in units of seconds), the units should
6543 * be defined as units of output per unit of the differentiated input
6544 * error. For example, when controlling velocity using a duty cycle
6545 * closed loop, the derivative of velocity with respect to time is rot
6546 * per sec², which is acceleration. Therefore, the units for the
6547 * derivative gain will be duty cycle per unit of acceleration error,
6548 * or 1/(rot per sec²).
6549 *
6550 * - Minimum Value: 0
6551 * - Maximum Value: 3.4e+38
6552 * - Default Value: 0
6553 * - Units:
6554 */
6555 units::dimensionless::scalar_t kD = 0;
6556 /**
6557 * \brief Static Feedforward Gain.
6558 *
6559 * \details This is added to the closed loop output. The unit for this
6560 * constant is dependent on the control mode, typically fractional
6561 * duty cycle, voltage, or torque current.
6562 *
6563 * The sign is typically determined by reference velocity when using
6564 * position, velocity, and Motion Magic® closed loop modes. However,
6565 * when using position closed loop with zero velocity reference (no
6566 * motion profiling), the application can instead use the position
6567 * closed loop error by setting the Static Feedforward Sign
6568 * configuration parameter. When doing so, we recommend the minimal
6569 * amount of kS, otherwise the motor output may dither when closed
6570 * loop error is near zero.
6571 *
6572 * - Minimum Value: -512
6573 * - Maximum Value: 511
6574 * - Default Value: 0
6575 * - Units:
6576 */
6577 units::dimensionless::scalar_t kS = 0;
6578 /**
6579 * \brief Velocity Feedforward Gain.
6580 *
6581 * \details The units for this gain is dependent on the control mode.
6582 * Since this gain is multiplied by the requested velocity, the units
6583 * should be defined as units of output per unit of requested input
6584 * velocity. For example, when controlling velocity using a duty cycle
6585 * closed loop, the units for the velocity feedfoward gain will be
6586 * duty cycle per requested rps, or 1/rps.
6587 *
6588 * - Minimum Value: 0
6589 * - Maximum Value: 3.4e+38
6590 * - Default Value: 0
6591 * - Units:
6592 */
6593 units::dimensionless::scalar_t kV = 0;
6594 /**
6595 * \brief Acceleration Feedforward Gain.
6596 *
6597 * \details The units for this gain is dependent on the control mode.
6598 * Since this gain is multiplied by the requested acceleration, the
6599 * units should be defined as units of output per unit of requested
6600 * input acceleration. For example, when controlling velocity using a
6601 * duty cycle closed loop, the units for the acceleration feedfoward
6602 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6603 * sec²).
6604 *
6605 * - Minimum Value: 0
6606 * - Maximum Value: 3.4e+38
6607 * - Default Value: 0
6608 * - Units:
6609 */
6610 units::dimensionless::scalar_t kA = 0;
6611 /**
6612 * \brief Gravity Feedforward/Feedback Gain.
6613 *
6614 * \details This is added to the closed loop output. The sign is
6615 * determined by GravityType. The unit for this constant is dependent
6616 * on the control mode, typically fractional duty cycle, voltage, or
6617 * torque current.
6618 *
6619 * - Minimum Value: -512
6620 * - Maximum Value: 511
6621 * - Default Value: 0
6622 * - Units:
6623 */
6624 units::dimensionless::scalar_t kG = 0;
6625 /**
6626 * \brief Gravity Feedforward/Feedback Type.
6627 *
6628 * This determines the type of the gravity feedforward/feedback.
6629 *
6630 * Choose Elevator_Static for systems where the gravity feedforward is
6631 * constant, such as an elevator. The gravity feedforward output will
6632 * always be positive.
6633 *
6634 * Choose Arm_Cosine for systems where the gravity feedback is
6635 * dependent on the angular position of the mechanism, such as an arm.
6636 * The gravity feedback output will vary depending on the mechanism
6637 * angular position. Note that the sensor offset and ratios must be
6638 * configured so that the sensor position is 0 when the mechanism is
6639 * horizonal, and one rotation of the mechanism corresponds to one
6640 * rotation of the sensor position.
6641 *
6642 */
6644 /**
6645 * \brief Static Feedforward Sign during position closed loop.
6646 *
6647 * This determines the sign of the applied kS during position
6648 * closed-loop modes. The default behavior uses the velocity reference
6649 * sign. This works well with velocity closed loop, Motion Magic®
6650 * controls, and position closed loop when velocity reference is
6651 * specified (motion profiling).
6652 *
6653 * However, when using position closed loop with zero velocity
6654 * reference (no motion profiling), the application may want to apply
6655 * static feedforward based on the closed loop error sign instead.
6656 * When doing so, we recommend using the minimal amount of kS,
6657 * otherwise the motor output may dither when closed loop error is
6658 * near zero.
6659 *
6660 */
6662
6663 /**
6664 * \brief Modifies this configuration's kP parameter and returns itself for
6665 * method-chaining and easier to use config API.
6666 *
6667 * Proportional Gain.
6668 *
6669 * \details The units for this gain is dependent on the control mode.
6670 * Since this gain is multiplied by error in the input, the units
6671 * should be defined as units of output per unit of input error. For
6672 * example, when controlling velocity using a duty cycle closed loop,
6673 * the units for the proportional gain will be duty cycle per rps, or
6674 * 1/rps.
6675 *
6676 * - Minimum Value: 0
6677 * - Maximum Value: 3.4e+38
6678 * - Default Value: 0
6679 * - Units:
6680 *
6681 * \param newKP Parameter to modify
6682 * \returns Itself
6683 */
6684 constexpr Slot1Configs &WithKP(units::dimensionless::scalar_t newKP)
6685 {
6686 kP = std::move(newKP);
6687 return *this;
6688 }
6689
6690 /**
6691 * \brief Modifies this configuration's kI parameter and returns itself for
6692 * method-chaining and easier to use config API.
6693 *
6694 * Integral Gain.
6695 *
6696 * \details The units for this gain is dependent on the control mode.
6697 * Since this gain is multiplied by error in the input integrated over
6698 * time (in units of seconds), the units should be defined as units of
6699 * output per unit of integrated input error. For example, when
6700 * controlling velocity using a duty cycle closed loop, integrating
6701 * velocity over time results in rps * s = rotations. Therefore, the
6702 * units for the integral gain will be duty cycle per rotation of
6703 * accumulated error, or 1/rot.
6704 *
6705 * - Minimum Value: 0
6706 * - Maximum Value: 3.4e+38
6707 * - Default Value: 0
6708 * - Units:
6709 *
6710 * \param newKI Parameter to modify
6711 * \returns Itself
6712 */
6713 constexpr Slot1Configs &WithKI(units::dimensionless::scalar_t newKI)
6714 {
6715 kI = std::move(newKI);
6716 return *this;
6717 }
6718
6719 /**
6720 * \brief Modifies this configuration's kD parameter and returns itself for
6721 * method-chaining and easier to use config API.
6722 *
6723 * Derivative Gain.
6724 *
6725 * \details The units for this gain is dependent on the control mode.
6726 * Since this gain is multiplied by the derivative of error in the
6727 * input with respect to time (in units of seconds), the units should
6728 * be defined as units of output per unit of the differentiated input
6729 * error. For example, when controlling velocity using a duty cycle
6730 * closed loop, the derivative of velocity with respect to time is rot
6731 * per sec², which is acceleration. Therefore, the units for the
6732 * derivative gain will be duty cycle per unit of acceleration error,
6733 * or 1/(rot per sec²).
6734 *
6735 * - Minimum Value: 0
6736 * - Maximum Value: 3.4e+38
6737 * - Default Value: 0
6738 * - Units:
6739 *
6740 * \param newKD Parameter to modify
6741 * \returns Itself
6742 */
6743 constexpr Slot1Configs &WithKD(units::dimensionless::scalar_t newKD)
6744 {
6745 kD = std::move(newKD);
6746 return *this;
6747 }
6748
6749 /**
6750 * \brief Modifies this configuration's kS parameter and returns itself for
6751 * method-chaining and easier to use config API.
6752 *
6753 * Static Feedforward Gain.
6754 *
6755 * \details This is added to the closed loop output. The unit for this
6756 * constant is dependent on the control mode, typically fractional
6757 * duty cycle, voltage, or torque current.
6758 *
6759 * The sign is typically determined by reference velocity when using
6760 * position, velocity, and Motion Magic® closed loop modes. However,
6761 * when using position closed loop with zero velocity reference (no
6762 * motion profiling), the application can instead use the position
6763 * closed loop error by setting the Static Feedforward Sign
6764 * configuration parameter. When doing so, we recommend the minimal
6765 * amount of kS, otherwise the motor output may dither when closed
6766 * loop error is near zero.
6767 *
6768 * - Minimum Value: -512
6769 * - Maximum Value: 511
6770 * - Default Value: 0
6771 * - Units:
6772 *
6773 * \param newKS Parameter to modify
6774 * \returns Itself
6775 */
6776 constexpr Slot1Configs &WithKS(units::dimensionless::scalar_t newKS)
6777 {
6778 kS = std::move(newKS);
6779 return *this;
6780 }
6781
6782 /**
6783 * \brief Modifies this configuration's kV parameter and returns itself for
6784 * method-chaining and easier to use config API.
6785 *
6786 * Velocity Feedforward Gain.
6787 *
6788 * \details The units for this gain is dependent on the control mode.
6789 * Since this gain is multiplied by the requested velocity, the units
6790 * should be defined as units of output per unit of requested input
6791 * velocity. For example, when controlling velocity using a duty cycle
6792 * closed loop, the units for the velocity feedfoward gain will be
6793 * duty cycle per requested rps, or 1/rps.
6794 *
6795 * - Minimum Value: 0
6796 * - Maximum Value: 3.4e+38
6797 * - Default Value: 0
6798 * - Units:
6799 *
6800 * \param newKV Parameter to modify
6801 * \returns Itself
6802 */
6803 constexpr Slot1Configs &WithKV(units::dimensionless::scalar_t newKV)
6804 {
6805 kV = std::move(newKV);
6806 return *this;
6807 }
6808
6809 /**
6810 * \brief Modifies this configuration's kA parameter and returns itself for
6811 * method-chaining and easier to use config API.
6812 *
6813 * Acceleration Feedforward Gain.
6814 *
6815 * \details The units for this gain is dependent on the control mode.
6816 * Since this gain is multiplied by the requested acceleration, the
6817 * units should be defined as units of output per unit of requested
6818 * input acceleration. For example, when controlling velocity using a
6819 * duty cycle closed loop, the units for the acceleration feedfoward
6820 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6821 * sec²).
6822 *
6823 * - Minimum Value: 0
6824 * - Maximum Value: 3.4e+38
6825 * - Default Value: 0
6826 * - Units:
6827 *
6828 * \param newKA Parameter to modify
6829 * \returns Itself
6830 */
6831 constexpr Slot1Configs &WithKA(units::dimensionless::scalar_t newKA)
6832 {
6833 kA = std::move(newKA);
6834 return *this;
6835 }
6836
6837 /**
6838 * \brief Modifies this configuration's kG parameter and returns itself for
6839 * method-chaining and easier to use config API.
6840 *
6841 * Gravity Feedforward/Feedback Gain.
6842 *
6843 * \details This is added to the closed loop output. The sign is
6844 * determined by GravityType. The unit for this constant is dependent
6845 * on the control mode, typically fractional duty cycle, voltage, or
6846 * torque current.
6847 *
6848 * - Minimum Value: -512
6849 * - Maximum Value: 511
6850 * - Default Value: 0
6851 * - Units:
6852 *
6853 * \param newKG Parameter to modify
6854 * \returns Itself
6855 */
6856 constexpr Slot1Configs &WithKG(units::dimensionless::scalar_t newKG)
6857 {
6858 kG = std::move(newKG);
6859 return *this;
6860 }
6861
6862 /**
6863 * \brief Modifies this configuration's GravityType parameter and returns itself for
6864 * method-chaining and easier to use config API.
6865 *
6866 * Gravity Feedforward/Feedback Type.
6867 *
6868 * This determines the type of the gravity feedforward/feedback.
6869 *
6870 * Choose Elevator_Static for systems where the gravity feedforward is
6871 * constant, such as an elevator. The gravity feedforward output will
6872 * always be positive.
6873 *
6874 * Choose Arm_Cosine for systems where the gravity feedback is
6875 * dependent on the angular position of the mechanism, such as an arm.
6876 * The gravity feedback output will vary depending on the mechanism
6877 * angular position. Note that the sensor offset and ratios must be
6878 * configured so that the sensor position is 0 when the mechanism is
6879 * horizonal, and one rotation of the mechanism corresponds to one
6880 * rotation of the sensor position.
6881 *
6882 *
6883 * \param newGravityType Parameter to modify
6884 * \returns Itself
6885 */
6887 {
6888 GravityType = std::move(newGravityType);
6889 return *this;
6890 }
6891
6892 /**
6893 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
6894 * method-chaining and easier to use config API.
6895 *
6896 * Static Feedforward Sign during position closed loop.
6897 *
6898 * This determines the sign of the applied kS during position
6899 * closed-loop modes. The default behavior uses the velocity reference
6900 * sign. This works well with velocity closed loop, Motion Magic®
6901 * controls, and position closed loop when velocity reference is
6902 * specified (motion profiling).
6903 *
6904 * However, when using position closed loop with zero velocity
6905 * reference (no motion profiling), the application may want to apply
6906 * static feedforward based on the closed loop error sign instead.
6907 * When doing so, we recommend using the minimal amount of kS,
6908 * otherwise the motor output may dither when closed loop error is
6909 * near zero.
6910 *
6911 *
6912 * \param newStaticFeedforwardSign Parameter to modify
6913 * \returns Itself
6914 */
6916 {
6917 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
6918 return *this;
6919 }
6920
6921 static Slot1Configs From(const SlotConfigs &value);
6922
6923 std::string ToString() const override
6924 {
6925 std::stringstream ss;
6926 ss << "Config Group: Slot1" << std::endl;
6927 ss << " kP: " << kP.to<double>() << std::endl;
6928 ss << " kI: " << kI.to<double>() << std::endl;
6929 ss << " kD: " << kD.to<double>() << std::endl;
6930 ss << " kS: " << kS.to<double>() << std::endl;
6931 ss << " kV: " << kV.to<double>() << std::endl;
6932 ss << " kA: " << kA.to<double>() << std::endl;
6933 ss << " kG: " << kG.to<double>() << std::endl;
6934 ss << " GravityType: " << GravityType << std::endl;
6935 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
6936 return ss.str();
6937 }
6938
6939 std::string Serialize() const override
6940 {
6941 std::stringstream ss;
6942 char *ref;
6943 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6944 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6945 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6946 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6947 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6948 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6949 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6950 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6951 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6952 return ss.str();
6953 }
6954
6955 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
6956 {
6957 const char *string_c_str = to_deserialize.c_str();
6958 size_t string_length = to_deserialize.length();
6959 double kPVal = kP.to<double>();
6960 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kP, string_c_str, string_length, &kPVal);
6961 kP = units::dimensionless::scalar_t{kPVal};
6962 double kIVal = kI.to<double>();
6963 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kI, string_c_str, string_length, &kIVal);
6964 kI = units::dimensionless::scalar_t{kIVal};
6965 double kDVal = kD.to<double>();
6966 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kD, string_c_str, string_length, &kDVal);
6967 kD = units::dimensionless::scalar_t{kDVal};
6968 double kSVal = kS.to<double>();
6969 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kS, string_c_str, string_length, &kSVal);
6970 kS = units::dimensionless::scalar_t{kSVal};
6971 double kVVal = kV.to<double>();
6972 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kV, string_c_str, string_length, &kVVal);
6973 kV = units::dimensionless::scalar_t{kVVal};
6974 double kAVal = kA.to<double>();
6975 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kA, string_c_str, string_length, &kAVal);
6976 kA = units::dimensionless::scalar_t{kAVal};
6977 double kGVal = kG.to<double>();
6978 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kG, string_c_str, string_length, &kGVal);
6979 kG = units::dimensionless::scalar_t{kGVal};
6980 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kG_Type, string_c_str, string_length, &GravityType.value);
6981 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
6982 return 0;
6983 }
6984};
6985
6986
6987/**
6988 * \brief Gains for the specified slot.
6989 *
6990 * \details If this slot is selected, these gains are used in closed
6991 * loop control requests.
6992 */
6994{
6995public:
6996 constexpr Slot2Configs() = default;
6997
6998 /**
6999 * \brief Proportional Gain.
7000 *
7001 * \details The units for this gain is dependent on the control mode.
7002 * Since this gain is multiplied by error in the input, the units
7003 * should be defined as units of output per unit of input error. For
7004 * example, when controlling velocity using a duty cycle closed loop,
7005 * the units for the proportional gain will be duty cycle per rps, or
7006 * 1/rps.
7007 *
7008 * - Minimum Value: 0
7009 * - Maximum Value: 3.4e+38
7010 * - Default Value: 0
7011 * - Units:
7012 */
7013 units::dimensionless::scalar_t kP = 0;
7014 /**
7015 * \brief Integral Gain.
7016 *
7017 * \details The units for this gain is dependent on the control mode.
7018 * Since this gain is multiplied by error in the input integrated over
7019 * time (in units of seconds), the units should be defined as units of
7020 * output per unit of integrated input error. For example, when
7021 * controlling velocity using a duty cycle closed loop, integrating
7022 * velocity over time results in rps * s = rotations. Therefore, the
7023 * units for the integral gain will be duty cycle per rotation of
7024 * accumulated error, or 1/rot.
7025 *
7026 * - Minimum Value: 0
7027 * - Maximum Value: 3.4e+38
7028 * - Default Value: 0
7029 * - Units:
7030 */
7031 units::dimensionless::scalar_t kI = 0;
7032 /**
7033 * \brief Derivative Gain.
7034 *
7035 * \details The units for this gain is dependent on the control mode.
7036 * Since this gain is multiplied by the derivative of error in the
7037 * input with respect to time (in units of seconds), the units should
7038 * be defined as units of output per unit of the differentiated input
7039 * error. For example, when controlling velocity using a duty cycle
7040 * closed loop, the derivative of velocity with respect to time is rot
7041 * per sec², which is acceleration. Therefore, the units for the
7042 * derivative gain will be duty cycle per unit of acceleration error,
7043 * or 1/(rot per sec²).
7044 *
7045 * - Minimum Value: 0
7046 * - Maximum Value: 3.4e+38
7047 * - Default Value: 0
7048 * - Units:
7049 */
7050 units::dimensionless::scalar_t kD = 0;
7051 /**
7052 * \brief Static Feedforward Gain.
7053 *
7054 * \details This is added to the closed loop output. The unit for this
7055 * constant is dependent on the control mode, typically fractional
7056 * duty cycle, voltage, or torque current.
7057 *
7058 * The sign is typically determined by reference velocity when using
7059 * position, velocity, and Motion Magic® closed loop modes. However,
7060 * when using position closed loop with zero velocity reference (no
7061 * motion profiling), the application can instead use the position
7062 * closed loop error by setting the Static Feedforward Sign
7063 * configuration parameter. When doing so, we recommend the minimal
7064 * amount of kS, otherwise the motor output may dither when closed
7065 * loop error is near zero.
7066 *
7067 * - Minimum Value: -512
7068 * - Maximum Value: 511
7069 * - Default Value: 0
7070 * - Units:
7071 */
7072 units::dimensionless::scalar_t kS = 0;
7073 /**
7074 * \brief Velocity Feedforward Gain.
7075 *
7076 * \details The units for this gain is dependent on the control mode.
7077 * Since this gain is multiplied by the requested velocity, the units
7078 * should be defined as units of output per unit of requested input
7079 * velocity. For example, when controlling velocity using a duty cycle
7080 * closed loop, the units for the velocity feedfoward gain will be
7081 * duty cycle per requested rps, or 1/rps.
7082 *
7083 * - Minimum Value: 0
7084 * - Maximum Value: 3.4e+38
7085 * - Default Value: 0
7086 * - Units:
7087 */
7088 units::dimensionless::scalar_t kV = 0;
7089 /**
7090 * \brief Acceleration Feedforward Gain.
7091 *
7092 * \details The units for this gain is dependent on the control mode.
7093 * Since this gain is multiplied by the requested acceleration, the
7094 * units should be defined as units of output per unit of requested
7095 * input acceleration. For example, when controlling velocity using a
7096 * duty cycle closed loop, the units for the acceleration feedfoward
7097 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7098 * sec²).
7099 *
7100 * - Minimum Value: 0
7101 * - Maximum Value: 3.4e+38
7102 * - Default Value: 0
7103 * - Units:
7104 */
7105 units::dimensionless::scalar_t kA = 0;
7106 /**
7107 * \brief Gravity Feedforward/Feedback Gain.
7108 *
7109 * \details This is added to the closed loop output. The sign is
7110 * determined by GravityType. The unit for this constant is dependent
7111 * on the control mode, typically fractional duty cycle, voltage, or
7112 * torque current.
7113 *
7114 * - Minimum Value: -512
7115 * - Maximum Value: 511
7116 * - Default Value: 0
7117 * - Units:
7118 */
7119 units::dimensionless::scalar_t kG = 0;
7120 /**
7121 * \brief Gravity Feedforward/Feedback Type.
7122 *
7123 * This determines the type of the gravity feedforward/feedback.
7124 *
7125 * Choose Elevator_Static for systems where the gravity feedforward is
7126 * constant, such as an elevator. The gravity feedforward output will
7127 * always be positive.
7128 *
7129 * Choose Arm_Cosine for systems where the gravity feedback is
7130 * dependent on the angular position of the mechanism, such as an arm.
7131 * The gravity feedback output will vary depending on the mechanism
7132 * angular position. Note that the sensor offset and ratios must be
7133 * configured so that the sensor position is 0 when the mechanism is
7134 * horizonal, and one rotation of the mechanism corresponds to one
7135 * rotation of the sensor position.
7136 *
7137 */
7139 /**
7140 * \brief Static Feedforward Sign during position closed loop.
7141 *
7142 * This determines the sign of the applied kS during position
7143 * closed-loop modes. The default behavior uses the velocity reference
7144 * sign. This works well with velocity closed loop, Motion Magic®
7145 * controls, and position closed loop when velocity reference is
7146 * specified (motion profiling).
7147 *
7148 * However, when using position closed loop with zero velocity
7149 * reference (no motion profiling), the application may want to apply
7150 * static feedforward based on the closed loop error sign instead.
7151 * When doing so, we recommend using the minimal amount of kS,
7152 * otherwise the motor output may dither when closed loop error is
7153 * near zero.
7154 *
7155 */
7157
7158 /**
7159 * \brief Modifies this configuration's kP parameter and returns itself for
7160 * method-chaining and easier to use config API.
7161 *
7162 * Proportional Gain.
7163 *
7164 * \details The units for this gain is dependent on the control mode.
7165 * Since this gain is multiplied by error in the input, the units
7166 * should be defined as units of output per unit of input error. For
7167 * example, when controlling velocity using a duty cycle closed loop,
7168 * the units for the proportional gain will be duty cycle per rps, or
7169 * 1/rps.
7170 *
7171 * - Minimum Value: 0
7172 * - Maximum Value: 3.4e+38
7173 * - Default Value: 0
7174 * - Units:
7175 *
7176 * \param newKP Parameter to modify
7177 * \returns Itself
7178 */
7179 constexpr Slot2Configs &WithKP(units::dimensionless::scalar_t newKP)
7180 {
7181 kP = std::move(newKP);
7182 return *this;
7183 }
7184
7185 /**
7186 * \brief Modifies this configuration's kI parameter and returns itself for
7187 * method-chaining and easier to use config API.
7188 *
7189 * Integral Gain.
7190 *
7191 * \details The units for this gain is dependent on the control mode.
7192 * Since this gain is multiplied by error in the input integrated over
7193 * time (in units of seconds), the units should be defined as units of
7194 * output per unit of integrated input error. For example, when
7195 * controlling velocity using a duty cycle closed loop, integrating
7196 * velocity over time results in rps * s = rotations. Therefore, the
7197 * units for the integral gain will be duty cycle per rotation of
7198 * accumulated error, or 1/rot.
7199 *
7200 * - Minimum Value: 0
7201 * - Maximum Value: 3.4e+38
7202 * - Default Value: 0
7203 * - Units:
7204 *
7205 * \param newKI Parameter to modify
7206 * \returns Itself
7207 */
7208 constexpr Slot2Configs &WithKI(units::dimensionless::scalar_t newKI)
7209 {
7210 kI = std::move(newKI);
7211 return *this;
7212 }
7213
7214 /**
7215 * \brief Modifies this configuration's kD parameter and returns itself for
7216 * method-chaining and easier to use config API.
7217 *
7218 * Derivative Gain.
7219 *
7220 * \details The units for this gain is dependent on the control mode.
7221 * Since this gain is multiplied by the derivative of error in the
7222 * input with respect to time (in units of seconds), the units should
7223 * be defined as units of output per unit of the differentiated input
7224 * error. For example, when controlling velocity using a duty cycle
7225 * closed loop, the derivative of velocity with respect to time is rot
7226 * per sec², which is acceleration. Therefore, the units for the
7227 * derivative gain will be duty cycle per unit of acceleration error,
7228 * or 1/(rot per sec²).
7229 *
7230 * - Minimum Value: 0
7231 * - Maximum Value: 3.4e+38
7232 * - Default Value: 0
7233 * - Units:
7234 *
7235 * \param newKD Parameter to modify
7236 * \returns Itself
7237 */
7238 constexpr Slot2Configs &WithKD(units::dimensionless::scalar_t newKD)
7239 {
7240 kD = std::move(newKD);
7241 return *this;
7242 }
7243
7244 /**
7245 * \brief Modifies this configuration's kS parameter and returns itself for
7246 * method-chaining and easier to use config API.
7247 *
7248 * Static Feedforward Gain.
7249 *
7250 * \details This is added to the closed loop output. The unit for this
7251 * constant is dependent on the control mode, typically fractional
7252 * duty cycle, voltage, or torque current.
7253 *
7254 * The sign is typically determined by reference velocity when using
7255 * position, velocity, and Motion Magic® closed loop modes. However,
7256 * when using position closed loop with zero velocity reference (no
7257 * motion profiling), the application can instead use the position
7258 * closed loop error by setting the Static Feedforward Sign
7259 * configuration parameter. When doing so, we recommend the minimal
7260 * amount of kS, otherwise the motor output may dither when closed
7261 * loop error is near zero.
7262 *
7263 * - Minimum Value: -512
7264 * - Maximum Value: 511
7265 * - Default Value: 0
7266 * - Units:
7267 *
7268 * \param newKS Parameter to modify
7269 * \returns Itself
7270 */
7271 constexpr Slot2Configs &WithKS(units::dimensionless::scalar_t newKS)
7272 {
7273 kS = std::move(newKS);
7274 return *this;
7275 }
7276
7277 /**
7278 * \brief Modifies this configuration's kV parameter and returns itself for
7279 * method-chaining and easier to use config API.
7280 *
7281 * Velocity Feedforward Gain.
7282 *
7283 * \details The units for this gain is dependent on the control mode.
7284 * Since this gain is multiplied by the requested velocity, the units
7285 * should be defined as units of output per unit of requested input
7286 * velocity. For example, when controlling velocity using a duty cycle
7287 * closed loop, the units for the velocity feedfoward gain will be
7288 * duty cycle per requested rps, or 1/rps.
7289 *
7290 * - Minimum Value: 0
7291 * - Maximum Value: 3.4e+38
7292 * - Default Value: 0
7293 * - Units:
7294 *
7295 * \param newKV Parameter to modify
7296 * \returns Itself
7297 */
7298 constexpr Slot2Configs &WithKV(units::dimensionless::scalar_t newKV)
7299 {
7300 kV = std::move(newKV);
7301 return *this;
7302 }
7303
7304 /**
7305 * \brief Modifies this configuration's kA parameter and returns itself for
7306 * method-chaining and easier to use config API.
7307 *
7308 * Acceleration Feedforward Gain.
7309 *
7310 * \details The units for this gain is dependent on the control mode.
7311 * Since this gain is multiplied by the requested acceleration, the
7312 * units should be defined as units of output per unit of requested
7313 * input acceleration. For example, when controlling velocity using a
7314 * duty cycle closed loop, the units for the acceleration feedfoward
7315 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7316 * sec²).
7317 *
7318 * - Minimum Value: 0
7319 * - Maximum Value: 3.4e+38
7320 * - Default Value: 0
7321 * - Units:
7322 *
7323 * \param newKA Parameter to modify
7324 * \returns Itself
7325 */
7326 constexpr Slot2Configs &WithKA(units::dimensionless::scalar_t newKA)
7327 {
7328 kA = std::move(newKA);
7329 return *this;
7330 }
7331
7332 /**
7333 * \brief Modifies this configuration's kG parameter and returns itself for
7334 * method-chaining and easier to use config API.
7335 *
7336 * Gravity Feedforward/Feedback Gain.
7337 *
7338 * \details This is added to the closed loop output. The sign is
7339 * determined by GravityType. The unit for this constant is dependent
7340 * on the control mode, typically fractional duty cycle, voltage, or
7341 * torque current.
7342 *
7343 * - Minimum Value: -512
7344 * - Maximum Value: 511
7345 * - Default Value: 0
7346 * - Units:
7347 *
7348 * \param newKG Parameter to modify
7349 * \returns Itself
7350 */
7351 constexpr Slot2Configs &WithKG(units::dimensionless::scalar_t newKG)
7352 {
7353 kG = std::move(newKG);
7354 return *this;
7355 }
7356
7357 /**
7358 * \brief Modifies this configuration's GravityType parameter and returns itself for
7359 * method-chaining and easier to use config API.
7360 *
7361 * Gravity Feedforward/Feedback Type.
7362 *
7363 * This determines the type of the gravity feedforward/feedback.
7364 *
7365 * Choose Elevator_Static for systems where the gravity feedforward is
7366 * constant, such as an elevator. The gravity feedforward output will
7367 * always be positive.
7368 *
7369 * Choose Arm_Cosine for systems where the gravity feedback is
7370 * dependent on the angular position of the mechanism, such as an arm.
7371 * The gravity feedback output will vary depending on the mechanism
7372 * angular position. Note that the sensor offset and ratios must be
7373 * configured so that the sensor position is 0 when the mechanism is
7374 * horizonal, and one rotation of the mechanism corresponds to one
7375 * rotation of the sensor position.
7376 *
7377 *
7378 * \param newGravityType Parameter to modify
7379 * \returns Itself
7380 */
7382 {
7383 GravityType = std::move(newGravityType);
7384 return *this;
7385 }
7386
7387 /**
7388 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
7389 * method-chaining and easier to use config API.
7390 *
7391 * Static Feedforward Sign during position closed loop.
7392 *
7393 * This determines the sign of the applied kS during position
7394 * closed-loop modes. The default behavior uses the velocity reference
7395 * sign. This works well with velocity closed loop, Motion Magic®
7396 * controls, and position closed loop when velocity reference is
7397 * specified (motion profiling).
7398 *
7399 * However, when using position closed loop with zero velocity
7400 * reference (no motion profiling), the application may want to apply
7401 * static feedforward based on the closed loop error sign instead.
7402 * When doing so, we recommend using the minimal amount of kS,
7403 * otherwise the motor output may dither when closed loop error is
7404 * near zero.
7405 *
7406 *
7407 * \param newStaticFeedforwardSign Parameter to modify
7408 * \returns Itself
7409 */
7411 {
7412 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
7413 return *this;
7414 }
7415
7416 static Slot2Configs From(const SlotConfigs &value);
7417
7418 std::string ToString() const override
7419 {
7420 std::stringstream ss;
7421 ss << "Config Group: Slot2" << std::endl;
7422 ss << " kP: " << kP.to<double>() << std::endl;
7423 ss << " kI: " << kI.to<double>() << std::endl;
7424 ss << " kD: " << kD.to<double>() << std::endl;
7425 ss << " kS: " << kS.to<double>() << std::endl;
7426 ss << " kV: " << kV.to<double>() << std::endl;
7427 ss << " kA: " << kA.to<double>() << std::endl;
7428 ss << " kG: " << kG.to<double>() << std::endl;
7429 ss << " GravityType: " << GravityType << std::endl;
7430 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
7431 return ss.str();
7432 }
7433
7434 std::string Serialize() const override
7435 {
7436 std::stringstream ss;
7437 char *ref;
7438 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7439 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7440 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7441 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7442 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7443 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7444 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7445 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7446 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7447 return ss.str();
7448 }
7449
7450 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
7451 {
7452 const char *string_c_str = to_deserialize.c_str();
7453 size_t string_length = to_deserialize.length();
7454 double kPVal = kP.to<double>();
7455 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kP, string_c_str, string_length, &kPVal);
7456 kP = units::dimensionless::scalar_t{kPVal};
7457 double kIVal = kI.to<double>();
7458 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kI, string_c_str, string_length, &kIVal);
7459 kI = units::dimensionless::scalar_t{kIVal};
7460 double kDVal = kD.to<double>();
7461 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kD, string_c_str, string_length, &kDVal);
7462 kD = units::dimensionless::scalar_t{kDVal};
7463 double kSVal = kS.to<double>();
7464 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kS, string_c_str, string_length, &kSVal);
7465 kS = units::dimensionless::scalar_t{kSVal};
7466 double kVVal = kV.to<double>();
7467 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kV, string_c_str, string_length, &kVVal);
7468 kV = units::dimensionless::scalar_t{kVVal};
7469 double kAVal = kA.to<double>();
7470 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kA, string_c_str, string_length, &kAVal);
7471 kA = units::dimensionless::scalar_t{kAVal};
7472 double kGVal = kG.to<double>();
7473 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kG, string_c_str, string_length, &kGVal);
7474 kG = units::dimensionless::scalar_t{kGVal};
7475 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kG_Type, string_c_str, string_length, &GravityType.value);
7476 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
7477 return 0;
7478 }
7479};
7480
7481/**
7482 * \brief Gains for the specified slot.
7483 *
7484 * \details If this slot is selected, these gains are used in closed
7485 * loop control requests.
7486 */
7488{
7489 struct SlotSpns
7490 {
7491 int kPSpn;
7492 int kISpn;
7493 int kDSpn;
7494 int kSSpn;
7495 int kVSpn;
7496 int kASpn;
7497 int kGSpn;
7498 int GravityTypeSpn;
7499 int StaticFeedforwardSignSpn;
7500 };
7501
7502 static inline std::map<int, SlotSpns> const genericMap{
7503 {0, SlotSpns{
7504 ctre::phoenix6::spns::SpnValue::Slot0_kP,
7505 ctre::phoenix6::spns::SpnValue::Slot0_kI,
7506 ctre::phoenix6::spns::SpnValue::Slot0_kD,
7507 ctre::phoenix6::spns::SpnValue::Slot0_kS,
7508 ctre::phoenix6::spns::SpnValue::Slot0_kV,
7509 ctre::phoenix6::spns::SpnValue::Slot0_kA,
7510 ctre::phoenix6::spns::SpnValue::Slot0_kG,
7511 ctre::phoenix6::spns::SpnValue::Slot0_kG_Type,
7512 ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign,
7513 }},
7514
7515 {1, SlotSpns{
7516 ctre::phoenix6::spns::SpnValue::Slot1_kP,
7517 ctre::phoenix6::spns::SpnValue::Slot1_kI,
7518 ctre::phoenix6::spns::SpnValue::Slot1_kD,
7519 ctre::phoenix6::spns::SpnValue::Slot1_kS,
7520 ctre::phoenix6::spns::SpnValue::Slot1_kV,
7521 ctre::phoenix6::spns::SpnValue::Slot1_kA,
7522 ctre::phoenix6::spns::SpnValue::Slot1_kG,
7523 ctre::phoenix6::spns::SpnValue::Slot1_kG_Type,
7524 ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign,
7525 }},
7526
7527 {2, SlotSpns{
7528 ctre::phoenix6::spns::SpnValue::Slot2_kP,
7529 ctre::phoenix6::spns::SpnValue::Slot2_kI,
7530 ctre::phoenix6::spns::SpnValue::Slot2_kD,
7531 ctre::phoenix6::spns::SpnValue::Slot2_kS,
7532 ctre::phoenix6::spns::SpnValue::Slot2_kV,
7533 ctre::phoenix6::spns::SpnValue::Slot2_kA,
7534 ctre::phoenix6::spns::SpnValue::Slot2_kG,
7535 ctre::phoenix6::spns::SpnValue::Slot2_kG_Type,
7536 ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign,
7537 }},
7538
7539 };
7540
7541public:
7542 constexpr SlotConfigs() = default;
7543
7544 /**
7545 * \brief Proportional Gain.
7546 *
7547 * \details The units for this gain is dependent on the control mode.
7548 * Since this gain is multiplied by error in the input, the units
7549 * should be defined as units of output per unit of input error. For
7550 * example, when controlling velocity using a duty cycle closed loop,
7551 * the units for the proportional gain will be duty cycle per rps of
7552 * error, or 1/rps.
7553 *
7554 * - Minimum Value: 0
7555 * - Maximum Value: 3.4e+38
7556 * - Default Value: 0
7557 * - Units:
7558 */
7559 units::dimensionless::scalar_t kP = 0;
7560 /**
7561 * \brief Integral Gain.
7562 *
7563 * \details The units for this gain is dependent on the control mode.
7564 * Since this gain is multiplied by error in the input integrated over
7565 * time (in units of seconds), the units should be defined as units of
7566 * output per unit of integrated input error. For example, when
7567 * controlling velocity using a duty cycle closed loop, integrating
7568 * velocity over time results in rps * s = rotations. Therefore, the
7569 * units for the integral gain will be duty cycle per rotation of
7570 * accumulated error, or 1/rot.
7571 *
7572 * - Minimum Value: 0
7573 * - Maximum Value: 3.4e+38
7574 * - Default Value: 0
7575 * - Units:
7576 */
7577 units::dimensionless::scalar_t kI = 0;
7578 /**
7579 * \brief Derivative Gain.
7580 *
7581 * \details The units for this gain is dependent on the control mode.
7582 * Since this gain is multiplied by the derivative of error in the
7583 * input with respect to time (in units of seconds), the units should
7584 * be defined as units of output per unit of the differentiated input
7585 * error. For example, when controlling velocity using a duty cycle
7586 * closed loop, the derivative of velocity with respect to time is rot
7587 * per sec², which is acceleration. Therefore, the units for the
7588 * derivative gain will be duty cycle per unit of acceleration error,
7589 * or 1/(rot per sec²).
7590 *
7591 * - Minimum Value: 0
7592 * - Maximum Value: 3.4e+38
7593 * - Default Value: 0
7594 * - Units:
7595 */
7596 units::dimensionless::scalar_t kD = 0;
7597 /**
7598 * \brief Static Feedforward Gain.
7599 *
7600 * \details This is added to the closed loop output. The unit for this
7601 * constant is dependent on the control mode, typically fractional
7602 * duty cycle, voltage, or torque current.
7603 *
7604 * The sign is typically determined by reference velocity when using
7605 * position, velocity, and Motion Magic® closed loop modes. However,
7606 * when using position closed loop with zero velocity reference (no
7607 * motion profiling), the application can instead use the position
7608 * closed loop error by setting the Static Feedforward Sign
7609 * configuration parameter. When doing so, we recommend the minimal
7610 * amount of kS, otherwise the motor output may dither when closed
7611 * loop error is near zero.
7612 *
7613 * - Minimum Value: -512
7614 * - Maximum Value: 511
7615 * - Default Value: 0
7616 * - Units:
7617 */
7618 units::dimensionless::scalar_t kS = 0;
7619 /**
7620 * \brief Velocity Feedforward Gain.
7621 *
7622 * \details The units for this gain is dependent on the control mode.
7623 * Since this gain is multiplied by the requested velocity, the units
7624 * should be defined as units of output per unit of requested input
7625 * velocity. For example, when controlling velocity using a duty cycle
7626 * closed loop, the units for the velocity feedfoward gain will be
7627 * duty cycle per requested rps, or 1/rps.
7628 *
7629 * - Minimum Value: 0
7630 * - Maximum Value: 3.4e+38
7631 * - Default Value: 0
7632 * - Units:
7633 */
7634 units::dimensionless::scalar_t kV = 0;
7635 /**
7636 * \brief Acceleration Feedforward Gain.
7637 *
7638 * \details The units for this gain is dependent on the control mode.
7639 * Since this gain is multiplied by the requested acceleration, the
7640 * units should be defined as units of output per unit of requested
7641 * input acceleration. For example, when controlling velocity using a
7642 * duty cycle closed loop, the units for the acceleration feedfoward
7643 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7644 * sec²).
7645 *
7646 * - Minimum Value: 0
7647 * - Maximum Value: 3.4e+38
7648 * - Default Value: 0
7649 * - Units:
7650 */
7651 units::dimensionless::scalar_t kA = 0;
7652 /**
7653 * \brief Gravity Feedforward/Feedback Gain.
7654 *
7655 * \details This is added to the closed loop output. The sign is
7656 * determined by GravityType. The unit for this constant is dependent
7657 * on the control mode, typically fractional duty cycle, voltage, or
7658 * torque current.
7659 *
7660 * - Minimum Value: -512
7661 * - Maximum Value: 511
7662 * - Default Value: 0
7663 * - Units:
7664 */
7665 units::dimensionless::scalar_t kG = 0;
7666 /**
7667 * \brief Gravity Feedforward/Feedback Type.
7668 *
7669 * This determines the type of the gravity feedforward/feedback.
7670 *
7671 * Choose Elevator_Static for systems where the gravity feedforward is
7672 * constant, such as an elevator. The gravity feedforward output will
7673 * always have the same sign.
7674 *
7675 * Choose Arm_Cosine for systems where the gravity feedback is
7676 * dependent on the angular position of the mechanism, such as an arm.
7677 * The gravity feedback output will vary depending on the mechanism
7678 * angular position. Note that the sensor offset and ratios must be
7679 * configured so that the sensor reports a position of 0 when the
7680 * mechanism is horizonal (parallel to the ground), and the reported
7681 * sensor position is 1:1 with the mechanism.
7682 *
7683 */
7685 /**
7686 * \brief Static Feedforward Sign during position closed loop.
7687 *
7688 * This determines the sign of the applied kS during position
7689 * closed-loop modes. The default behavior uses the velocity reference
7690 * sign. This works well with velocity closed loop, Motion Magic®
7691 * controls, and position closed loop when velocity reference is
7692 * specified (motion profiling).
7693 *
7694 * However, when using position closed loop with zero velocity
7695 * reference (no motion profiling), the application may want to apply
7696 * static feedforward based on the sign of closed loop error instead.
7697 * When doing so, we recommend using the minimal amount of kS,
7698 * otherwise the motor output may dither when closed loop error is
7699 * near zero.
7700 *
7701 */
7703
7704 /**
7705 * \brief Modifies this configuration's kP parameter and returns itself for
7706 * method-chaining and easier to use config API.
7707 *
7708 * Proportional Gain.
7709 *
7710 * \details The units for this gain is dependent on the control mode.
7711 * Since this gain is multiplied by error in the input, the units
7712 * should be defined as units of output per unit of input error. For
7713 * example, when controlling velocity using a duty cycle closed loop,
7714 * the units for the proportional gain will be duty cycle per rps of
7715 * error, or 1/rps.
7716 *
7717 * - Minimum Value: 0
7718 * - Maximum Value: 3.4e+38
7719 * - Default Value: 0
7720 * - Units:
7721 *
7722 * \param newKP Parameter to modify
7723 * \returns Itself
7724 */
7725 constexpr SlotConfigs &WithKP(units::dimensionless::scalar_t newKP)
7726 {
7727 kP = std::move(newKP);
7728 return *this;
7729 }
7730
7731 /**
7732 * \brief Modifies this configuration's kI parameter and returns itself for
7733 * method-chaining and easier to use config API.
7734 *
7735 * Integral Gain.
7736 *
7737 * \details The units for this gain is dependent on the control mode.
7738 * Since this gain is multiplied by error in the input integrated over
7739 * time (in units of seconds), the units should be defined as units of
7740 * output per unit of integrated input error. For example, when
7741 * controlling velocity using a duty cycle closed loop, integrating
7742 * velocity over time results in rps * s = rotations. Therefore, the
7743 * units for the integral gain will be duty cycle per rotation of
7744 * accumulated error, or 1/rot.
7745 *
7746 * - Minimum Value: 0
7747 * - Maximum Value: 3.4e+38
7748 * - Default Value: 0
7749 * - Units:
7750 *
7751 * \param newKI Parameter to modify
7752 * \returns Itself
7753 */
7754 constexpr SlotConfigs &WithKI(units::dimensionless::scalar_t newKI)
7755 {
7756 kI = std::move(newKI);
7757 return *this;
7758 }
7759
7760 /**
7761 * \brief Modifies this configuration's kD parameter and returns itself for
7762 * method-chaining and easier to use config API.
7763 *
7764 * Derivative Gain.
7765 *
7766 * \details The units for this gain is dependent on the control mode.
7767 * Since this gain is multiplied by the derivative of error in the
7768 * input with respect to time (in units of seconds), the units should
7769 * be defined as units of output per unit of the differentiated input
7770 * error. For example, when controlling velocity using a duty cycle
7771 * closed loop, the derivative of velocity with respect to time is rot
7772 * per sec², which is acceleration. Therefore, the units for the
7773 * derivative gain will be duty cycle per unit of acceleration error,
7774 * or 1/(rot per sec²).
7775 *
7776 * - Minimum Value: 0
7777 * - Maximum Value: 3.4e+38
7778 * - Default Value: 0
7779 * - Units:
7780 *
7781 * \param newKD Parameter to modify
7782 * \returns Itself
7783 */
7784 constexpr SlotConfigs &WithKD(units::dimensionless::scalar_t newKD)
7785 {
7786 kD = std::move(newKD);
7787 return *this;
7788 }
7789
7790 /**
7791 * \brief Modifies this configuration's kS parameter and returns itself for
7792 * method-chaining and easier to use config API.
7793 *
7794 * Static Feedforward Gain.
7795 *
7796 * \details This is added to the closed loop output. The unit for this
7797 * constant is dependent on the control mode, typically fractional
7798 * duty cycle, voltage, or torque current.
7799 *
7800 * The sign is typically determined by reference velocity when using
7801 * position, velocity, and Motion Magic® closed loop modes. However,
7802 * when using position closed loop with zero velocity reference (no
7803 * motion profiling), the application can instead use the position
7804 * closed loop error by setting the Static Feedforward Sign
7805 * configuration parameter. When doing so, we recommend the minimal
7806 * amount of kS, otherwise the motor output may dither when closed
7807 * loop error is near zero.
7808 *
7809 * - Minimum Value: -512
7810 * - Maximum Value: 511
7811 * - Default Value: 0
7812 * - Units:
7813 *
7814 * \param newKS Parameter to modify
7815 * \returns Itself
7816 */
7817 constexpr SlotConfigs &WithKS(units::dimensionless::scalar_t newKS)
7818 {
7819 kS = std::move(newKS);
7820 return *this;
7821 }
7822
7823 /**
7824 * \brief Modifies this configuration's kV parameter and returns itself for
7825 * method-chaining and easier to use config API.
7826 *
7827 * Velocity Feedforward Gain.
7828 *
7829 * \details The units for this gain is dependent on the control mode.
7830 * Since this gain is multiplied by the requested velocity, the units
7831 * should be defined as units of output per unit of requested input
7832 * velocity. For example, when controlling velocity using a duty cycle
7833 * closed loop, the units for the velocity feedfoward gain will be
7834 * duty cycle per requested rps, or 1/rps.
7835 *
7836 * - Minimum Value: 0
7837 * - Maximum Value: 3.4e+38
7838 * - Default Value: 0
7839 * - Units:
7840 *
7841 * \param newKV Parameter to modify
7842 * \returns Itself
7843 */
7844 constexpr SlotConfigs &WithKV(units::dimensionless::scalar_t newKV)
7845 {
7846 kV = std::move(newKV);
7847 return *this;
7848 }
7849
7850 /**
7851 * \brief Modifies this configuration's kA parameter and returns itself for
7852 * method-chaining and easier to use config API.
7853 *
7854 * Acceleration Feedforward Gain.
7855 *
7856 * \details The units for this gain is dependent on the control mode.
7857 * Since this gain is multiplied by the requested acceleration, the
7858 * units should be defined as units of output per unit of requested
7859 * input acceleration. For example, when controlling velocity using a
7860 * duty cycle closed loop, the units for the acceleration feedfoward
7861 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7862 * sec²).
7863 *
7864 * - Minimum Value: 0
7865 * - Maximum Value: 3.4e+38
7866 * - Default Value: 0
7867 * - Units:
7868 *
7869 * \param newKA Parameter to modify
7870 * \returns Itself
7871 */
7872 constexpr SlotConfigs &WithKA(units::dimensionless::scalar_t newKA)
7873 {
7874 kA = std::move(newKA);
7875 return *this;
7876 }
7877
7878 /**
7879 * \brief Modifies this configuration's kG parameter and returns itself for
7880 * method-chaining and easier to use config API.
7881 *
7882 * Gravity Feedforward/Feedback Gain.
7883 *
7884 * \details This is added to the closed loop output. The sign is
7885 * determined by GravityType. The unit for this constant is dependent
7886 * on the control mode, typically fractional duty cycle, voltage, or
7887 * torque current.
7888 *
7889 * - Minimum Value: -512
7890 * - Maximum Value: 511
7891 * - Default Value: 0
7892 * - Units:
7893 *
7894 * \param newKG Parameter to modify
7895 * \returns Itself
7896 */
7897 constexpr SlotConfigs &WithKG(units::dimensionless::scalar_t newKG)
7898 {
7899 kG = std::move(newKG);
7900 return *this;
7901 }
7902
7903 /**
7904 * \brief Modifies this configuration's GravityType parameter and returns itself for
7905 * method-chaining and easier to use config API.
7906 *
7907 * Gravity Feedforward/Feedback Type.
7908 *
7909 * This determines the type of the gravity feedforward/feedback.
7910 *
7911 * Choose Elevator_Static for systems where the gravity feedforward is
7912 * constant, such as an elevator. The gravity feedforward output will
7913 * always have the same sign.
7914 *
7915 * Choose Arm_Cosine for systems where the gravity feedback is
7916 * dependent on the angular position of the mechanism, such as an arm.
7917 * The gravity feedback output will vary depending on the mechanism
7918 * angular position. Note that the sensor offset and ratios must be
7919 * configured so that the sensor reports a position of 0 when the
7920 * mechanism is horizonal (parallel to the ground), and the reported
7921 * sensor position is 1:1 with the mechanism.
7922 *
7923 *
7924 * \param newGravityType Parameter to modify
7925 * \returns Itself
7926 */
7928 {
7929 GravityType = std::move(newGravityType);
7930 return *this;
7931 }
7932
7933 /**
7934 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
7935 * method-chaining and easier to use config API.
7936 *
7937 * Static Feedforward Sign during position closed loop.
7938 *
7939 * This determines the sign of the applied kS during position
7940 * closed-loop modes. The default behavior uses the velocity reference
7941 * sign. This works well with velocity closed loop, Motion Magic®
7942 * controls, and position closed loop when velocity reference is
7943 * specified (motion profiling).
7944 *
7945 * However, when using position closed loop with zero velocity
7946 * reference (no motion profiling), the application may want to apply
7947 * static feedforward based on the sign of closed loop error instead.
7948 * When doing so, we recommend using the minimal amount of kS,
7949 * otherwise the motor output may dither when closed loop error is
7950 * near zero.
7951 *
7952 *
7953 * \param newStaticFeedforwardSign Parameter to modify
7954 * \returns Itself
7955 */
7957 {
7958 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
7959 return *this;
7960 }
7961
7962
7963 /**
7964 * \brief Chooses which slot these configs are for.
7965 */
7966 int SlotNumber = 0;
7967
7968 static SlotConfigs From(const Slot0Configs &value);
7969 static SlotConfigs From(const Slot1Configs &value);
7970 static SlotConfigs From(const Slot2Configs &value);
7971
7972 std::string ToString() const
7973 {
7974 std::stringstream ss;
7975 ss << "Config Group: Slot" << std::endl;
7976 ss << " kP: " << kP.to<double>() << std::endl;
7977 ss << " kI: " << kI.to<double>() << std::endl;
7978 ss << " kD: " << kD.to<double>() << std::endl;
7979 ss << " kS: " << kS.to<double>() << std::endl;
7980 ss << " kV: " << kV.to<double>() << std::endl;
7981 ss << " kA: " << kA.to<double>() << std::endl;
7982 ss << " kG: " << kG.to<double>() << std::endl;
7983 ss << " GravityType: " << GravityType << std::endl;
7984 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
7985 return ss.str();
7986 }
7987
7988 std::string Serialize() const
7989 {
7990 std::stringstream ss;
7991 SlotSpns currentSpns = genericMap.at(SlotNumber);
7992 char *ref;
7993 c_ctre_phoenix6_serialize_double(currentSpns.kPSpn, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7994 c_ctre_phoenix6_serialize_double(currentSpns.kISpn, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7995 c_ctre_phoenix6_serialize_double(currentSpns.kDSpn, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7996 c_ctre_phoenix6_serialize_double(currentSpns.kSSpn, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7997 c_ctre_phoenix6_serialize_double(currentSpns.kVSpn, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7998 c_ctre_phoenix6_serialize_double(currentSpns.kASpn, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7999 c_ctre_phoenix6_serialize_double(currentSpns.kGSpn, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
8000 c_ctre_phoenix6_serialize_int(currentSpns.GravityTypeSpn, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
8001 c_ctre_phoenix6_serialize_int(currentSpns.StaticFeedforwardSignSpn, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
8002 return ss.str();
8003 }
8004
8005 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
8006 {
8007 const char *string_c_str = to_deserialize.c_str();
8008 size_t string_length = to_deserialize.length();
8009 SlotSpns currentSpns = genericMap.at(SlotNumber);
8010 double kPVal = kP.to<double>();
8011 c_ctre_phoenix6_deserialize_double(currentSpns.kPSpn, string_c_str, string_length, &kPVal);
8012 kP = units::dimensionless::scalar_t{kPVal};
8013 double kIVal = kI.to<double>();
8014 c_ctre_phoenix6_deserialize_double(currentSpns.kISpn, string_c_str, string_length, &kIVal);
8015 kI = units::dimensionless::scalar_t{kIVal};
8016 double kDVal = kD.to<double>();
8017 c_ctre_phoenix6_deserialize_double(currentSpns.kDSpn, string_c_str, string_length, &kDVal);
8018 kD = units::dimensionless::scalar_t{kDVal};
8019 double kSVal = kS.to<double>();
8020 c_ctre_phoenix6_deserialize_double(currentSpns.kSSpn, string_c_str, string_length, &kSVal);
8021 kS = units::dimensionless::scalar_t{kSVal};
8022 double kVVal = kV.to<double>();
8023 c_ctre_phoenix6_deserialize_double(currentSpns.kVSpn, string_c_str, string_length, &kVVal);
8024 kV = units::dimensionless::scalar_t{kVVal};
8025 double kAVal = kA.to<double>();
8026 c_ctre_phoenix6_deserialize_double(currentSpns.kASpn, string_c_str, string_length, &kAVal);
8027 kA = units::dimensionless::scalar_t{kAVal};
8028 double kGVal = kG.to<double>();
8029 c_ctre_phoenix6_deserialize_double(currentSpns.kGSpn, string_c_str, string_length, &kGVal);
8030 kG = units::dimensionless::scalar_t{kGVal};
8031 c_ctre_phoenix6_deserialize_int(currentSpns.GravityTypeSpn, string_c_str, string_length, &GravityType.value);
8032 c_ctre_phoenix6_deserialize_int(currentSpns.StaticFeedforwardSignSpn, string_c_str, string_length, &StaticFeedforwardSign.value);
8033 return 0;
8034 }
8035};
8036
8037
8038}
8039}
8040}
ii that the Software will be uninterrupted or error free
Definition CTRE_LICENSE.txt:251
CTREXPORT int c_ctre_phoenix6_deserialize_double(int spn, const char *str, uint32_t strlen, double *val)
CTREXPORT int c_ctre_phoenix6_serialize_int(int spn, int value, char **str)
CTREXPORT int c_ctre_phoenix6_serialize_bool(int spn, bool value, char **str)
CTREXPORT int c_ctre_phoenix6_deserialize_bool(int spn, const char *str, uint32_t strlen, bool *val)
CTREXPORT int c_ctre_phoenix6_deserialize_int(int spn, const char *str, uint32_t strlen, int *val)
CTREXPORT int c_ctre_phoenix6_serialize_double(int spn, double value, char **str)
Definition Serializable.hpp:15
Configs that affect audible components of the device.
Definition Configs.hpp:3993
bool BeepOnConfig
If true, the TalonFX will beep during configuration API calls if device is disabled.
Definition Configs.hpp:4014
bool AllowMusicDurDisable
If true, the TalonFX will allow Orchestra and MusicTone requests during disabled state.
Definition Configs.hpp:4024
std::string Serialize() const override
Definition Configs.hpp:4098
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4108
std::string ToString() const override
Definition Configs.hpp:4088
constexpr AudioConfigs & WithBeepOnBoot(bool newBeepOnBoot)
Modifies this configuration's BeepOnBoot parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:4039
constexpr AudioConfigs & WithAllowMusicDurDisable(bool newAllowMusicDurDisable)
Modifies this configuration's AllowMusicDurDisable parameter and returns itself for method-chaining a...
Definition Configs.hpp:4080
constexpr AudioConfigs & WithBeepOnConfig(bool newBeepOnConfig)
Modifies this configuration's BeepOnConfig parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4059
bool BeepOnBoot
If true, the TalonFX will beep during boot-up.
Definition Configs.hpp:4005
Configs that affect general behavior during closed-looping.
Definition Configs.hpp:4652
bool ContinuousWrap
Wrap position error within [-0.5,+0.5) mechanism rotations.
Definition Configs.hpp:4668
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4712
constexpr ClosedLoopGeneralConfigs & WithContinuousWrap(bool newContinuousWrap)
Modifies this configuration's ContinuousWrap parameter and returns itself for method-chaining and eas...
Definition Configs.hpp:4688
std::string ToString() const override
Definition Configs.hpp:4696
std::string Serialize() const override
Definition Configs.hpp:4704
Configs that affect the closed-loop control of this motor controller.
Definition Configs.hpp:3224
constexpr ClosedLoopRampsConfigs & WithDutyCycleClosedLoopRampPeriod(units::time::second_t newDutyCycleClosedLoopRampPeriod)
Modifies this configuration's DutyCycleClosedLoopRampPeriod parameter and returns itself for method-c...
Definition Configs.hpp:3305
std::string Serialize() const override
Definition Configs.hpp:3382
units::time::second_t DutyCycleClosedLoopRampPeriod
If non-zero, this determines how much time to ramp from 0% output to 100% during the closed-loop Duty...
Definition Configs.hpp:3244
constexpr ClosedLoopRampsConfigs & WithTorqueClosedLoopRampPeriod(units::time::second_t newTorqueClosedLoopRampPeriod)
Modifies this configuration's TorqueClosedLoopRampPeriod parameter and returns itself for method-chai...
Definition Configs.hpp:3364
constexpr ClosedLoopRampsConfigs & WithVoltageClosedLoopRampPeriod(units::time::second_t newVoltageClosedLoopRampPeriod)
Modifies this configuration's VoltageClosedLoopRampPeriod parameter and returns itself for method-cha...
Definition Configs.hpp:3333
units::time::second_t TorqueClosedLoopRampPeriod
If non-zero, this determines how much time to ramp from 0A output to 300A during the closed-loop Torq...
Definition Configs.hpp:3281
units::time::second_t VoltageClosedLoopRampPeriod
If non-zero, this determines how much time to ramp from 0V output to 12V during the closed-loop Volta...
Definition Configs.hpp:3261
std::string ToString() const override
Definition Configs.hpp:3372
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3392
Configs that determine motor selection and commutation.
Definition Configs.hpp:5210
std::string ToString() const override
Definition Configs.hpp:5304
constexpr CommutationConfigs & WithAdvancedHallSupport(signals::AdvancedHallSupportValue newAdvancedHallSupport)
Modifies this configuration's AdvancedHallSupport parameter and returns itself for method-chaining an...
Definition Configs.hpp:5256
signals::BrushedMotorWiringValue BrushedMotorWiring
If a brushed motor is selected with Motor Arrangement, this config determines which of three leads to...
Definition Configs.hpp:5240
signals::AdvancedHallSupportValue AdvancedHallSupport
Requires Phoenix Pro; Improves commutation and velocity measurement for motors with hall sensors.
Definition Configs.hpp:5222
std::string Serialize() const override
Definition Configs.hpp:5314
signals::MotorArrangementValue MotorArrangement
Selects the motor and motor connections used with Talon.
Definition Configs.hpp:5234
constexpr CommutationConfigs & WithBrushedMotorWiring(signals::BrushedMotorWiringValue newBrushedMotorWiring)
Modifies this configuration's BrushedMotorWiring parameter and returns itself for method-chaining and...
Definition Configs.hpp:5296
constexpr CommutationConfigs & WithMotorArrangement(signals::MotorArrangementValue newMotorArrangement)
Modifies this configuration's MotorArrangement parameter and returns itself for method-chaining and e...
Definition Configs.hpp:5279
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5324
Configs that directly affect current limiting features.
Definition Configs.hpp:888
bool StatorCurrentLimitEnable
Enable motor stator current limiting.
Definition Configs.hpp:924
std::string Serialize() const override
Definition Configs.hpp:1149
constexpr CurrentLimitsConfigs & WithSupplyCurrentLimitEnable(bool newSupplyCurrentLimitEnable)
Modifies this configuration's SupplyCurrentLimitEnable parameter and returns itself for method-chaini...
Definition Configs.hpp:1081
constexpr CurrentLimitsConfigs & WithSupplyCurrentLimit(units::current::ampere_t newSupplyCurrentLimit)
Modifies this configuration's SupplyCurrentLimit parameter and returns itself for method-chaining and...
Definition Configs.hpp:1064
units::current::ampere_t SupplyCurrentLimit
The absolute maximum amount of supply current allowed.
Definition Configs.hpp:948
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:1162
units::current::ampere_t StatorCurrentLimit
The amount of current allowed in the motor (motoring and regen current).
Definition Configs.hpp:918
constexpr CurrentLimitsConfigs & WithSupplyCurrentLowerTime(units::time::second_t newSupplyCurrentLowerTime)
Modifies this configuration's SupplyCurrentLowerTime parameter and returns itself for method-chaining...
Definition Configs.hpp:1128
constexpr CurrentLimitsConfigs & WithSupplyCurrentLowerLimit(units::current::ampere_t newSupplyCurrentLowerLimit)
Modifies this configuration's SupplyCurrentLowerLimit parameter and returns itself for method-chainin...
Definition Configs.hpp:1106
constexpr CurrentLimitsConfigs & WithStatorCurrentLimit(units::current::ampere_t newStatorCurrentLimit)
Modifies this configuration's StatorCurrentLimit parameter and returns itself for method-chaining and...
Definition Configs.hpp:1012
units::current::ampere_t SupplyCurrentLowerLimit
The amount of supply current allowed after the regular SupplyCurrentLimit is active for longer than S...
Definition Configs.hpp:968
std::string ToString() const override
Definition Configs.hpp:1136
bool SupplyCurrentLimitEnable
Enable motor supply current limiting.
Definition Configs.hpp:954
constexpr CurrentLimitsConfigs & WithStatorCurrentLimitEnable(bool newStatorCurrentLimitEnable)
Modifies this configuration's StatorCurrentLimitEnable parameter and returns itself for method-chaini...
Definition Configs.hpp:1029
units::time::second_t SupplyCurrentLowerTime
Reduces supply current to the SupplyCurrentLowerLimit after limiting to SupplyCurrentLimit for this p...
Definition Configs.hpp:979
Custom Params.
Definition Configs.hpp:4548
std::string ToString() const override
Definition Configs.hpp:4617
int CustomParam0
Custom parameter 0.
Definition Configs.hpp:4561
std::string Serialize() const override
Definition Configs.hpp:4626
int CustomParam1
Custom parameter 1.
Definition Configs.hpp:4571
constexpr CustomParamsConfigs & WithCustomParam0(int newCustomParam0)
Modifies this configuration's CustomParam0 parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4588
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4635
constexpr CustomParamsConfigs & WithCustomParam1(int newCustomParam1)
Modifies this configuration's CustomParam1 parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4609
Configs related to constants used for differential control of a mechanism.
Definition Configs.hpp:2912
units::current::ampere_t PeakDifferentialTorqueCurrent
Maximum differential output during torque current based differential control modes.
Definition Configs.hpp:2945
std::string Serialize() const override
Definition Configs.hpp:3022
std::string ToString() const override
Definition Configs.hpp:3012
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3032
constexpr DifferentialConstantsConfigs & WithPeakDifferentialVoltage(units::voltage::volt_t newPeakDifferentialVoltage)
Modifies this configuration's PeakDifferentialVoltage parameter and returns itself for method-chainin...
Definition Configs.hpp:2983
units::dimensionless::scalar_t PeakDifferentialDutyCycle
Maximum differential output during duty cycle based differential control modes.
Definition Configs.hpp:2925
constexpr DifferentialConstantsConfigs & WithPeakDifferentialTorqueCurrent(units::current::ampere_t newPeakDifferentialTorqueCurrent)
Modifies this configuration's PeakDifferentialTorqueCurrent parameter and returns itself for method-c...
Definition Configs.hpp:3004
constexpr DifferentialConstantsConfigs & WithPeakDifferentialDutyCycle(units::dimensionless::scalar_t newPeakDifferentialDutyCycle)
Modifies this configuration's PeakDifferentialDutyCycle parameter and returns itself for method-chain...
Definition Configs.hpp:2962
units::voltage::volt_t PeakDifferentialVoltage
Maximum differential output during voltage based differential control modes.
Definition Configs.hpp:2935
Configs related to sensors used for differential control of a mechanism.
Definition Configs.hpp:2733
constexpr DifferentialSensorsConfigs & WithDifferentialTalonFXSensorID(int newDifferentialTalonFXSensorID)
Modifies this configuration's DifferentialTalonFXSensorID parameter and returns itself for method-cha...
Definition Configs.hpp:2843
constexpr DifferentialSensorsConfigs & WithDifferentialSensorSource(signals::DifferentialSensorSourceValue newDifferentialSensorSource)
Modifies this configuration's DifferentialSensorSource parameter and returns itself for method-chaini...
Definition Configs.hpp:2822
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:2893
std::string Serialize() const override
Definition Configs.hpp:2883
std::string ToString() const override
Definition Configs.hpp:2873
signals::DifferentialSensorSourceValue DifferentialSensorSource
Choose what sensor source is used for differential control of a mechanism.
Definition Configs.hpp:2765
int DifferentialRemoteSensorID
Device ID of which remote sensor to use on the differential axis.
Definition Configs.hpp:2786
constexpr DifferentialSensorsConfigs & WithDifferentialRemoteSensorID(int newDifferentialRemoteSensorID)
Modifies this configuration's DifferentialRemoteSensorID parameter and returns itself for method-chai...
Definition Configs.hpp:2865
int DifferentialTalonFXSensorID
Device ID of which remote Talon FX to use.
Definition Configs.hpp:2775
Configs related to the CANdi™ branded device's digital I/O settings.
Definition Configs.hpp:5344
signals::S1CloseStateValue S1CloseState
What value the Signal 1 input (S1IN) needs to be for the CTR Electronics' CANdi™ to detect as Closed.
Definition Configs.hpp:5366
constexpr DigitalInputsConfigs & WithS2FloatState(signals::S2FloatStateValue newS2FloatState)
Modifies this configuration's S2FloatState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5403
signals::S2FloatStateValue S2FloatState
The floating state of the Signal 2 input (S2IN).
Definition Configs.hpp:5357
constexpr DigitalInputsConfigs & WithS2CloseState(signals::S2CloseStateValue newS2CloseState)
Modifies this configuration's S2CloseState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5443
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5473
std::string ToString() const override
Definition Configs.hpp:5451
signals::S2CloseStateValue S2CloseState
What value the Signal 2 input (S2IN) needs to be for the CTR Electronics' CANdi™ to detect as Closed.
Definition Configs.hpp:5375
constexpr DigitalInputsConfigs & WithS1CloseState(signals::S1CloseStateValue newS1CloseState)
Modifies this configuration's S1CloseState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5423
std::string Serialize() const override
Definition Configs.hpp:5462
signals::S1FloatStateValue S1FloatState
The floating state of the Signal 1 input (S1IN).
Definition Configs.hpp:5352
constexpr DigitalInputsConfigs & WithS1FloatState(signals::S1FloatStateValue newS1FloatState)
Modifies this configuration's S1FloatState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5387
Configs that affect the external feedback sensor of this motor controller.
Definition Configs.hpp:2007
constexpr ExternalFeedbackConfigs & WithSensorPhase(signals::SensorPhaseValue newSensorPhase)
Modifies this configuration's SensorPhase parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:2422
units::dimensionless::scalar_t SensorToMechanismRatio
The ratio of sensor rotations to the mechanism's output, where a ratio greater than 1 is a reduction.
Definition Configs.hpp:2030
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:2698
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:2207
units::time::second_t VelocityFilterTimeConstant
The configurable time constant of the Kalman velocity filter.
Definition Configs.hpp:2072
constexpr ExternalFeedbackConfigs & WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for method-chai...
Definition Configs.hpp:2309
ExternalFeedbackConfigs & WithSyncCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use SyncCANdi PWM 1 by passing in the CANdi object.
ExternalFeedbackConfigs & WithSyncCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use SyncCANcoder by passing in the CANcoder object.
signals::ExternalFeedbackSensorSourceValue ExternalFeedbackSensorSource
Choose what sensor source is reported via API and used by closed-loop and limit features.
Definition Configs.hpp:2136
units::dimensionless::scalar_t RotorToSensorRatio
The ratio of motor rotor rotations to remote sensor rotations, where a ratio greater than 1 is a redu...
Definition Configs.hpp:2047
ExternalFeedbackConfigs & WithFusedCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi PWM 2 by passing in the CANdi object...
ExternalFeedbackConfigs & WithRemoteCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi PWM 1 by passing in the CANdi objec...
constexpr ExternalFeedbackConfigs & WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for method-chai...
Definition Configs.hpp:2455
ExternalFeedbackConfigs & WithFusedCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi PWM 1 by passing in the CANdi object...
constexpr ExternalFeedbackConfigs & WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for method-chaining...
Definition Configs.hpp:2283
ExternalFeedbackConfigs & WithFusedCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi Quadrature by passing in the CANdi o...
ExternalFeedbackConfigs & WithRemoteCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use RemoteCANcoder by passing in the CANcoder objec...
constexpr ExternalFeedbackConfigs & WithExternalFeedbackSensorSource(signals::ExternalFeedbackSensorSourceValue newExternalFeedbackSensorSource)
Modifies this configuration's ExternalFeedbackSensorSource parameter and returns itself for method-ch...
Definition Configs.hpp:2395
constexpr ExternalFeedbackConfigs & WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
Modifies this configuration's RotorToSensorRatio parameter and returns itself for method-chaining and...
Definition Configs.hpp:2262
ExternalFeedbackConfigs & WithSyncCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use SyncCANdi PWM 2 by passing in the CANdi object.
std::string ToString() const override
Definition Configs.hpp:2666
signals::SensorPhaseValue SensorPhase
The relationship between the motor controlled by a Talon and the external sensor connected to the dat...
Definition Configs.hpp:2152
ExternalFeedbackConfigs & WithFusedCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use FusedCANcoder by passing in the CANcoder object...
units::angle::turn_t AbsoluteSensorOffset
The offset applied to any absolute sensor connected to the Talon data port.
Definition Configs.hpp:2086
ExternalFeedbackConfigs & WithRemoteCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi Quadrature by passing in the CANdi ...
int FeedbackRemoteSensorID
Device ID of which remote device to use.
Definition Configs.hpp:2057
constexpr ExternalFeedbackConfigs & WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
Modifies this configuration's SensorToMechanismRatio parameter and returns itself for method-chaining...
Definition Configs.hpp:2234
constexpr ExternalFeedbackConfigs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:2499
std::string Serialize() const override
Definition Configs.hpp:2682
ExternalFeedbackConfigs & WithRemoteCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi PWM 2 by passing in the CANdi objec...
int QuadratureEdgesPerRotation
The number of quadrature edges in one rotation for the quadrature sensor connected to the Talon data ...
Definition Configs.hpp:2174
constexpr ExternalFeedbackConfigs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:2334
Configs that affect the feedback of this motor controller.
Definition Configs.hpp:1487
FeedbackConfigs & WithSyncCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use SyncCANdi PWM 2 by passing in the CANdi object.
FeedbackConfigs & WithFusedCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi PWM 1 by passing in the CANdi object...
std::string ToString() const override
Definition Configs.hpp:1948
signals::FeedbackSensorSourceValue FeedbackSensorSource
Choose what sensor source is reported via API and used by closed-loop and limit features.
Definition Configs.hpp:1580
constexpr FeedbackConfigs & WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
Modifies this configuration's RotorToSensorRatio parameter and returns itself for method-chaining and...
Definition Configs.hpp:1682
FeedbackConfigs & WithRemoteCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use RemoteCANcoder by passing in the CANcoder objec...
FeedbackConfigs & WithRemoteCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi PWM 2 by passing in the CANdi objec...
FeedbackConfigs & WithRemoteCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi Quadrature by passing in the CANdi ...
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:1974
constexpr FeedbackConfigs & WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
Modifies this configuration's SensorToMechanismRatio parameter and returns itself for method-chaining...
Definition Configs.hpp:1654
units::dimensionless::scalar_t SensorToMechanismRatio
The ratio of sensor rotations to the mechanism's output, where a ratio greater than 1 is a reduction.
Definition Configs.hpp:1521
FeedbackConfigs & WithSyncCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use SyncCANcoder by passing in the CANcoder object.
std::string Serialize() const override
Definition Configs.hpp:1961
FeedbackConfigs & WithRemoteCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi PWM 1 by passing in the CANdi objec...
constexpr FeedbackConfigs & WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for method-chai...
Definition Configs.hpp:1782
FeedbackConfigs & WithFusedCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi Quadrature by passing in the CANdi o...
units::angle::turn_t FeedbackRotorOffset
The offset applied to the absolute integrated rotor sensor.
Definition Configs.hpp:1501
FeedbackConfigs & WithSyncCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use SyncCANdi PWM 1 by passing in the CANdi object.
units::time::second_t VelocityFilterTimeConstant
The configurable time constant of the Kalman velocity filter.
Definition Configs.hpp:1605
units::dimensionless::scalar_t RotorToSensorRatio
The ratio of motor rotor rotations to remote sensor rotations, where a ratio greater than 1 is a redu...
Definition Configs.hpp:1538
int FeedbackRemoteSensorID
Device ID of which remote device to use.
Definition Configs.hpp:1590
FeedbackConfigs & WithFusedCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use FusedCANdi PWM 2 by passing in the CANdi object...
constexpr FeedbackConfigs & WithFeedbackSensorSource(signals::FeedbackSensorSourceValue newFeedbackSensorSource)
Modifies this configuration's FeedbackSensorSource parameter and returns itself for method-chaining a...
Definition Configs.hpp:1735
FeedbackConfigs & WithFusedCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use FusedCANcoder by passing in the CANcoder object...
constexpr FeedbackConfigs & WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for method-chaining...
Definition Configs.hpp:1756
constexpr FeedbackConfigs & WithFeedbackRotorOffset(units::angle::turn_t newFeedbackRotorOffset)
Modifies this configuration's FeedbackRotorOffset parameter and returns itself for method-chaining an...
Definition Configs.hpp:1623
Configs that affect the ToF Field of View.
Definition Configs.hpp:4997
constexpr FovParamsConfigs & WithFOVRangeX(units::angle::degree_t newFOVRangeX)
Modifies this configuration's FOVRangeX parameter and returns itself for method-chaining and easier t...
Definition Configs.hpp:5126
std::string ToString() const override
Definition Configs.hpp:5160
units::angle::degree_t FOVCenterY
Specifies the target center of the Field of View in the Y direction.
Definition Configs.hpp:5026
constexpr FovParamsConfigs & WithFOVRangeY(units::angle::degree_t newFOVRangeY)
Modifies this configuration's FOVRangeY parameter and returns itself for method-chaining and easier t...
Definition Configs.hpp:5152
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5182
units::angle::degree_t FOVRangeX
Specifies the target range of the Field of View in the X direction.
Definition Configs.hpp:5041
constexpr FovParamsConfigs & WithFOVCenterX(units::angle::degree_t newFOVCenterX)
Modifies this configuration's FOVCenterX parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:5076
std::string Serialize() const override
Definition Configs.hpp:5171
units::angle::degree_t FOVCenterX
Specifies the target center of the Field of View in the X direction.
Definition Configs.hpp:5013
constexpr FovParamsConfigs & WithFOVCenterY(units::angle::degree_t newFOVCenterY)
Modifies this configuration's FOVCenterY parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:5100
units::angle::degree_t FOVRangeY
Specifies the target range of the Field of View in the Y direction.
Definition Configs.hpp:5056
Configs to trim the Pigeon2's gyroscope.
Definition Configs.hpp:388
constexpr GyroTrimConfigs & WithGyroScalarX(units::dimensionless::scalar_t newGyroScalarX)
Modifies this configuration's GyroScalarX parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:434
constexpr GyroTrimConfigs & WithGyroScalarY(units::dimensionless::scalar_t newGyroScalarY)
Modifies this configuration's GyroScalarY parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:454
std::string Serialize() const override
Definition Configs.hpp:492
std::string ToString() const override
Definition Configs.hpp:482
units::dimensionless::scalar_t GyroScalarY
The gyro scalar component for the Y axis.
Definition Configs.hpp:409
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:502
units::dimensionless::scalar_t GyroScalarX
The gyro scalar component for the X axis.
Definition Configs.hpp:400
constexpr GyroTrimConfigs & WithGyroScalarZ(units::dimensionless::scalar_t newGyroScalarZ)
Modifies this configuration's GyroScalarZ parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:474
units::dimensionless::scalar_t GyroScalarZ
The gyro scalar component for the Z axis.
Definition Configs.hpp:418
Configs that change how the motor controller behaves under different limit switch states.
Definition Configs.hpp:3419
HardwareLimitSwitchConfigs & WithReverseLimitRemoteTalonFX(const hardware::core::CoreTalonFX &device)
Helper method to configure this feedback group to use RemoteTalonFX reverse limit switch by passing i...
std::string ToString() const override
Definition Configs.hpp:3924
HardwareLimitSwitchConfigs & WithForwardLimitRemoteCANrange(const hardware::core::CoreCANrange &device)
Helper method to configure this feedback group to use the RemoteCANrange by passing in the CANrange o...
signals::ForwardLimitTypeValue ForwardLimitType
Determines if the forward limit switch is normally-open (default) or normally-closed.
Definition Configs.hpp:3428
constexpr HardwareLimitSwitchConfigs & WithForwardLimitAutosetPositionValue(units::angle::turn_t newForwardLimitAutosetPositionValue)
Modifies this configuration's ForwardLimitAutosetPositionValue parameter and returns itself for metho...
Definition Configs.hpp:3600
units::angle::turn_t ForwardLimitAutosetPositionValue
The value to automatically set the position to when the forward limit switch is asserted.
Definition Configs.hpp:3447
signals::ForwardLimitSourceValue ForwardLimitSource
Determines where to poll the forward limit switch.
Definition Configs.hpp:3474
constexpr HardwareLimitSwitchConfigs & WithForwardLimitEnable(bool newForwardLimitEnable)
Modifies this configuration's ForwardLimitEnable parameter and returns itself for method-chaining and...
Definition Configs.hpp:3618
bool ForwardLimitEnable
If enabled, motor output is set to neutral when the forward limit switch is asserted and positive out...
Definition Configs.hpp:3454
bool ReverseLimitAutosetPositionEnable
If enabled, the position is automatically set to a specific value, specified by ReverseLimitAutosetPo...
Definition Configs.hpp:3498
bool ForwardLimitAutosetPositionEnable
If enabled, the position is automatically set to a specific value, specified by ForwardLimitAutosetPo...
Definition Configs.hpp:3436
constexpr HardwareLimitSwitchConfigs & WithReverseLimitAutosetPositionValue(units::angle::turn_t newReverseLimitAutosetPositionValue)
Modifies this configuration's ReverseLimitAutosetPositionValue parameter and returns itself for metho...
Definition Configs.hpp:3727
constexpr HardwareLimitSwitchConfigs & WithReverseLimitSource(signals::ReverseLimitSourceValue newReverseLimitSource)
Modifies this configuration's ReverseLimitSource parameter and returns itself for method-chaining and...
Definition Configs.hpp:3775
signals::ReverseLimitTypeValue ReverseLimitType
Determines if the reverse limit switch is normally-open (default) or normally-closed.
Definition Configs.hpp:3490
units::angle::turn_t ReverseLimitAutosetPositionValue
The value to automatically set the position to when the reverse limit switch is asserted.
Definition Configs.hpp:3509
HardwareLimitSwitchConfigs & WithForwardLimitRemoteCANdiS1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi forward limit switch on Signal 1 In...
constexpr HardwareLimitSwitchConfigs & WithForwardLimitAutosetPositionEnable(bool newForwardLimitAutosetPositionEnable)
Modifies this configuration's ForwardLimitAutosetPositionEnable parameter and returns itself for meth...
Definition Configs.hpp:3578
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3962
constexpr HardwareLimitSwitchConfigs & WithForwardLimitRemoteSensorID(int newForwardLimitRemoteSensorID)
Modifies this configuration's ForwardLimitRemoteSensorID parameter and returns itself for method-chai...
Definition Configs.hpp:3669
constexpr HardwareLimitSwitchConfigs & WithReverseLimitAutosetPositionEnable(bool newReverseLimitAutosetPositionEnable)
Modifies this configuration's ReverseLimitAutosetPositionEnable parameter and returns itself for meth...
Definition Configs.hpp:3705
HardwareLimitSwitchConfigs & WithReverseLimitRemoteCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use RemoteCANcoder reverse limit switch by passing ...
constexpr HardwareLimitSwitchConfigs & WithReverseLimitType(signals::ReverseLimitTypeValue newReverseLimitType)
Modifies this configuration's ReverseLimitType parameter and returns itself for method-chaining and e...
Definition Configs.hpp:3686
HardwareLimitSwitchConfigs & WithForwardLimitRemoteCANdiS2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi forward limit switch on Signal 2 In...
constexpr HardwareLimitSwitchConfigs & WithReverseLimitEnable(bool newReverseLimitEnable)
Modifies this configuration's ReverseLimitEnable parameter and returns itself for method-chaining and...
Definition Configs.hpp:3745
int ForwardLimitRemoteSensorID
Device ID of the remote device if using remote limit switch features for the forward limit switch.
Definition Configs.hpp:3484
constexpr HardwareLimitSwitchConfigs & WithForwardLimitType(signals::ForwardLimitTypeValue newForwardLimitType)
Modifies this configuration's ForwardLimitType parameter and returns itself for method-chaining and e...
Definition Configs.hpp:3559
signals::ReverseLimitSourceValue ReverseLimitSource
Determines where to poll the reverse limit switch.
Definition Configs.hpp:3536
HardwareLimitSwitchConfigs & WithReverseLimitRemoteCANrange(const hardware::core::CoreCANrange &device)
Helper method to configure this feedback group to use the RemoteCANrange by passing in the CANrange o...
HardwareLimitSwitchConfigs & WithForwardLimitRemoteTalonFX(const hardware::core::CoreTalonFX &device)
Helper method to configure this feedback group to use RemoteTalonFX forward limit switch by passing i...
std::string Serialize() const override
Definition Configs.hpp:3943
HardwareLimitSwitchConfigs & WithReverseLimitRemoteCANdiS2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi reverse limit switch on Signal 2 In...
constexpr HardwareLimitSwitchConfigs & WithReverseLimitRemoteSensorID(int newReverseLimitRemoteSensorID)
Modifies this configuration's ReverseLimitRemoteSensorID parameter and returns itself for method-chai...
Definition Configs.hpp:3796
constexpr HardwareLimitSwitchConfigs & WithForwardLimitSource(signals::ForwardLimitSourceValue newForwardLimitSource)
Modifies this configuration's ForwardLimitSource parameter and returns itself for method-chaining and...
Definition Configs.hpp:3648
HardwareLimitSwitchConfigs & WithReverseLimitRemoteCANdiS1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use RemoteCANdi reverse limit switch on Signal 1 In...
HardwareLimitSwitchConfigs & WithForwardLimitRemoteCANcoder(const hardware::core::CoreCANcoder &device)
Helper method to configure this feedback group to use RemoteCANcoder forward limit switch by passing ...
bool ReverseLimitEnable
If enabled, motor output is set to neutral when reverse limit switch is asseted and negative output i...
Definition Configs.hpp:3516
int ReverseLimitRemoteSensorID
Device ID of the remote device if using remote limit switch features for the reverse limit switch.
Definition Configs.hpp:3546
Configs that affect the magnet sensor and how to interpret it.
Definition Configs.hpp:60
std::string Serialize() const override
Definition Configs.hpp:212
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:114
constexpr MagnetSensorConfigs & WithMagnetOffset(units::angle::turn_t newMagnetOffset)
Modifies this configuration's MagnetOffset parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:150
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:222
constexpr MagnetSensorConfigs & WithSensorDirection(signals::SensorDirectionValue newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:127
constexpr MagnetSensorConfigs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:194
units::angle::turn_t MagnetOffset
This offset is added to the reported position, allowing the application to trim the zero position.
Definition Configs.hpp:81
std::string ToString() const override
Definition Configs.hpp:202
signals::SensorDirectionValue SensorDirection
Direction of the sensor to determine positive rotation, as seen facing the LED side of the CANcoder.
Definition Configs.hpp:69
Configs for Motion Magic®.
Definition Configs.hpp:4292
ctre::unit::volts_per_turn_per_second_squared_t MotionMagicExpo_kA
This is the target kA used only by Motion Magic® Expo control modes.
Definition Configs.hpp:4366
constexpr MotionMagicConfigs & WithMotionMagicAcceleration(units::angular_acceleration::turns_per_second_squared_t newMotionMagicAcceleration)
Modifies this configuration's MotionMagicAcceleration parameter and returns itself for method-chainin...
Definition Configs.hpp:4410
ctre::unit::volts_per_turn_per_second_t MotionMagicExpo_kV
This is the target kV used only by Motion Magic® Expo control modes.
Definition Configs.hpp:4351
std::string Serialize() const override
Definition Configs.hpp:4506
constexpr MotionMagicConfigs & WithMotionMagicCruiseVelocity(units::angular_velocity::turns_per_second_t newMotionMagicCruiseVelocity)
Modifies this configuration's MotionMagicCruiseVelocity parameter and returns itself for method-chain...
Definition Configs.hpp:4388
units::angular_acceleration::turns_per_second_squared_t MotionMagicAcceleration
This is the target acceleration Motion Magic® based control modes are allowed to use.
Definition Configs.hpp:4321
constexpr MotionMagicConfigs & WithMotionMagicJerk(units::angular_jerk::turns_per_second_cubed_t newMotionMagicJerk)
Modifies this configuration's MotionMagicJerk parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:4436
units::angular_velocity::turns_per_second_t MotionMagicCruiseVelocity
This is the maximum velocity Motion Magic® based control modes are allowed to use.
Definition Configs.hpp:4310
units::angular_jerk::turns_per_second_cubed_t MotionMagicJerk
This is the target jerk (acceleration derivative) Motion Magic® based control modes are allowed to us...
Definition Configs.hpp:4336
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4518
std::string ToString() const override
Definition Configs.hpp:4494
constexpr MotionMagicConfigs & WithMotionMagicExpo_kA(ctre::unit::volts_per_turn_per_second_squared_t newMotionMagicExpo_kA)
Modifies this configuration's MotionMagicExpo_kA parameter and returns itself for method-chaining and...
Definition Configs.hpp:4486
constexpr MotionMagicConfigs & WithMotionMagicExpo_kV(ctre::unit::volts_per_turn_per_second_t newMotionMagicExpo_kV)
Modifies this configuration's MotionMagicExpo_kV parameter and returns itself for method-chaining and...
Definition Configs.hpp:4461
Configs that directly affect motor output.
Definition Configs.hpp:647
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:858
units::dimensionless::scalar_t PeakReverseDutyCycle
Minimum (reverse) output during duty cycle based control modes.
Definition Configs.hpp:692
signals::NeutralModeValue NeutralMode
The state of the motor controller bridge when output is neutral or disabled.
Definition Configs.hpp:662
constexpr MotorOutputConfigs & WithNeutralMode(signals::NeutralModeValue newNeutralMode)
Modifies this configuration's NeutralMode parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:737
constexpr MotorOutputConfigs & WithControlTimesyncFreqHz(units::frequency::hertz_t newControlTimesyncFreqHz)
Modifies this configuration's ControlTimesyncFreqHz parameter and returns itself for method-chaining ...
Definition Configs.hpp:824
units::dimensionless::scalar_t PeakForwardDutyCycle
Maximum (forward) output during duty cycle based control modes.
Definition Configs.hpp:682
constexpr MotorOutputConfigs & WithPeakForwardDutyCycle(units::dimensionless::scalar_t newPeakForwardDutyCycle)
Modifies this configuration's PeakForwardDutyCycle parameter and returns itself for method-chaining a...
Definition Configs.hpp:778
constexpr MotorOutputConfigs & WithDutyCycleNeutralDeadband(units::dimensionless::scalar_t newDutyCycleNeutralDeadband)
Modifies this configuration's DutyCycleNeutralDeadband parameter and returns itself for method-chaini...
Definition Configs.hpp:758
std::string ToString() const override
Definition Configs.hpp:832
signals::InvertedValue Inverted
Invert state of the device as seen from the front of the motor.
Definition Configs.hpp:656
std::string Serialize() const override
Definition Configs.hpp:845
constexpr MotorOutputConfigs & WithInverted(signals::InvertedValue newInverted)
Modifies this configuration's Inverted parameter and returns itself for method-chaining and easier to...
Definition Configs.hpp:720
constexpr MotorOutputConfigs & WithPeakReverseDutyCycle(units::dimensionless::scalar_t newPeakReverseDutyCycle)
Modifies this configuration's PeakReverseDutyCycle parameter and returns itself for method-chaining a...
Definition Configs.hpp:798
units::dimensionless::scalar_t DutyCycleNeutralDeadband
Configures the output deadband duty cycle during duty cycle and voltage based control modes.
Definition Configs.hpp:672
units::frequency::hertz_t ControlTimesyncFreqHz
When a control request UseTimesync is enabled, this determines the time-sychronized frequency at whic...
Definition Configs.hpp:708
Configs for Pigeon 2's Mount Pose configuration.
Definition Configs.hpp:246
constexpr MountPoseConfigs & WithMountPoseRoll(units::angle::degree_t newMountPoseRoll)
Modifies this configuration's MountPoseRoll parameter and returns itself for method-chaining and easi...
Definition Configs.hpp:332
constexpr MountPoseConfigs & WithMountPoseYaw(units::angle::degree_t newMountPoseYaw)
Modifies this configuration's MountPoseYaw parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:292
units::angle::degree_t MountPoseRoll
The mounting calibration roll-component.
Definition Configs.hpp:276
units::angle::degree_t MountPosePitch
The mounting calibration pitch-component.
Definition Configs.hpp:267
std::string ToString() const override
Definition Configs.hpp:340
constexpr MountPoseConfigs & WithMountPosePitch(units::angle::degree_t newMountPosePitch)
Modifies this configuration's MountPosePitch parameter and returns itself for method-chaining and eas...
Definition Configs.hpp:312
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:360
units::angle::degree_t MountPoseYaw
The mounting calibration yaw-component.
Definition Configs.hpp:258
std::string Serialize() const override
Definition Configs.hpp:350
Configs that affect the open-loop control of this motor controller.
Definition Configs.hpp:3057
constexpr OpenLoopRampsConfigs & WithVoltageOpenLoopRampPeriod(units::time::second_t newVoltageOpenLoopRampPeriod)
Modifies this configuration's VoltageOpenLoopRampPeriod parameter and returns itself for method-chain...
Definition Configs.hpp:3147
std::string Serialize() const override
Definition Configs.hpp:3189
constexpr OpenLoopRampsConfigs & WithDutyCycleOpenLoopRampPeriod(units::time::second_t newDutyCycleOpenLoopRampPeriod)
Modifies this configuration's DutyCycleOpenLoopRampPeriod parameter and returns itself for method-cha...
Definition Configs.hpp:3122
units::time::second_t VoltageOpenLoopRampPeriod
If non-zero, this determines how much time to ramp from 0V output to 12V during the open-loop Voltage...
Definition Configs.hpp:3088
units::time::second_t TorqueOpenLoopRampPeriod
If non-zero, this determines how much time to ramp from 0A output to 300A during the open-loop Torque...
Definition Configs.hpp:3101
std::string ToString() const override
Definition Configs.hpp:3179
constexpr OpenLoopRampsConfigs & WithTorqueOpenLoopRampPeriod(units::time::second_t newTorqueOpenLoopRampPeriod)
Modifies this configuration's TorqueOpenLoopRampPeriod parameter and returns itself for method-chaini...
Definition Configs.hpp:3171
units::time::second_t DutyCycleOpenLoopRampPeriod
If non-zero, this determines how much time to ramp from 0% output to 100% during the open-loop DutyCy...
Definition Configs.hpp:3074
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3199
Configs related to the CANdi™ branded device's PWM interface on the Signal 1 input (S1IN)
Definition Configs.hpp:5623
constexpr PWM1Configs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5761
units::angle::turn_t AbsoluteSensorOffset
The offset applied to the PWM sensor.
Definition Configs.hpp:5638
constexpr PWM1Configs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:5698
bool SensorDirection
Direction of the PWM sensor to determine positive rotation.
Definition Configs.hpp:5679
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5789
std::string ToString() const override
Definition Configs.hpp:5769
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:5671
constexpr PWM1Configs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:5742
std::string Serialize() const override
Definition Configs.hpp:5779
Configs related to the CANdi™ branded device's PWM interface on the Signal 2 input (S2IN)
Definition Configs.hpp:5815
units::angle::turn_t AbsoluteSensorOffset
The offset applied to the PWM sensor.
Definition Configs.hpp:5830
std::string Serialize() const override
Definition Configs.hpp:5971
constexpr PWM2Configs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:5934
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:5863
constexpr PWM2Configs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:5890
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5981
std::string ToString() const override
Definition Configs.hpp:5961
constexpr PWM2Configs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5953
bool SensorDirection
Direction of the PWM sensor to determine positive rotation.
Definition Configs.hpp:5871
friend std::ostream & operator<<(std::ostream &str, const ParentConfiguration &v)
Definition Configs.hpp:43
virtual ctre::phoenix::StatusCode Deserialize(const std::string &string)=0
virtual std::string ToString() const =0
Configs to enable/disable various features of the Pigeon2.
Definition Configs.hpp:527
constexpr Pigeon2FeaturesConfigs & WithEnableCompass(bool newEnableCompass)
Modifies this configuration's EnableCompass parameter and returns itself for method-chaining and easi...
Definition Configs.hpp:566
bool DisableTemperatureCompensation
Disables using the temperature compensation feature.
Definition Configs.hpp:545
constexpr Pigeon2FeaturesConfigs & WithDisableTemperatureCompensation(bool newDisableTemperatureCompensation)
Modifies this configuration's DisableTemperatureCompensation parameter and returns itself for method-...
Definition Configs.hpp:583
std::string ToString() const override
Definition Configs.hpp:608
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:628
std::string Serialize() const override
Definition Configs.hpp:618
bool DisableNoMotionCalibration
Disables using the no-motion calibration feature.
Definition Configs.hpp:551
constexpr Pigeon2FeaturesConfigs & WithDisableNoMotionCalibration(bool newDisableNoMotionCalibration)
Modifies this configuration's DisableNoMotionCalibration parameter and returns itself for method-chai...
Definition Configs.hpp:600
bool EnableCompass
Turns on or off the magnetometer fusing for 9-axis.
Definition Configs.hpp:539
Configs that affect the ToF Proximity detection.
Definition Configs.hpp:4829
units::dimensionless::scalar_t MinSignalStrengthForValidMeasurement
The minimum allowable signal strength before determining the measurement is valid.
Definition Configs.hpp:4874
std::string ToString() const override
Definition Configs.hpp:4953
constexpr ProximityParamsConfigs & WithProximityThreshold(units::length::meter_t newProximityThreshold)
Modifies this configuration's ProximityThreshold parameter and returns itself for method-chaining and...
Definition Configs.hpp:4890
constexpr ProximityParamsConfigs & WithMinSignalStrengthForValidMeasurement(units::dimensionless::scalar_t newMinSignalStrengthForValidMeasurement)
Modifies this configuration's MinSignalStrengthForValidMeasurement parameter and returns itself for m...
Definition Configs.hpp:4945
std::string Serialize() const override
Definition Configs.hpp:4963
units::length::meter_t ProximityThreshold
Threshold for object detection.
Definition Configs.hpp:4841
constexpr ProximityParamsConfigs & WithProximityHysteresis(units::length::meter_t newProximityHysteresis)
Modifies this configuration's ProximityHysteresis parameter and returns itself for method-chaining an...
Definition Configs.hpp:4918
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4973
units::length::meter_t ProximityHysteresis
How far above and below the threshold the distance needs to be to trigger undetected and detected,...
Definition Configs.hpp:4858
Configs related to the CANdi™ branded device's quadrature interface using both the S1IN and S2IN inpu...
Definition Configs.hpp:5495
int QuadratureEdgesPerRotation
The number of quadrature edges in one rotation for the quadrature sensor connected to the Talon data ...
Definition Configs.hpp:5520
std::string ToString() const override
Definition Configs.hpp:5584
constexpr QuadratureConfigs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5576
std::string Serialize() const override
Definition Configs.hpp:5593
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5602
bool SensorDirection
Direction of the quadrature sensor to determine positive rotation.
Definition Configs.hpp:5528
constexpr QuadratureConfigs & WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for method-chai...
Definition Configs.hpp:5557
Gains for the specified slot.
Definition Configs.hpp:6004
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:6082
constexpr Slot0Configs & WithKI(units::dimensionless::scalar_t newKI)
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6218
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:6115
static Slot0Configs From(const SlotConfigs &value)
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:6166
constexpr Slot0Configs & WithKA(units::dimensionless::scalar_t newKA)
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6336
std::string ToString() const override
Definition Configs.hpp:6428
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:6148
constexpr Slot0Configs & WithKS(units::dimensionless::scalar_t newKS)
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6281
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:6023
constexpr Slot0Configs & WithKP(units::dimensionless::scalar_t newKP)
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6189
constexpr Slot0Configs & WithKV(units::dimensionless::scalar_t newKV)
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6308
constexpr Slot0Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:6420
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:6460
constexpr Slot0Configs & WithKG(units::dimensionless::scalar_t newKG)
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6361
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:6060
constexpr Slot0Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:6391
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:6098
constexpr Slot0Configs & WithKD(units::dimensionless::scalar_t newKD)
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6248
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:6129
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:6041
std::string Serialize() const override
Definition Configs.hpp:6444
Gains for the specified slot.
Definition Configs.hpp:6499
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:6518
std::string Serialize() const override
Definition Configs.hpp:6939
static Slot1Configs From(const SlotConfigs &value)
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:6624
constexpr Slot1Configs & WithKI(units::dimensionless::scalar_t newKI)
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6713
constexpr Slot1Configs & WithKS(units::dimensionless::scalar_t newKS)
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6776
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:6610
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:6577
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:6555
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:6536
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:6661
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:6593
constexpr Slot1Configs & WithKP(units::dimensionless::scalar_t newKP)
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6684
constexpr Slot1Configs & WithKG(units::dimensionless::scalar_t newKG)
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6856
constexpr Slot1Configs & WithKV(units::dimensionless::scalar_t newKV)
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6803
constexpr Slot1Configs & WithKD(units::dimensionless::scalar_t newKD)
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6743
constexpr Slot1Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:6915
constexpr Slot1Configs & WithKA(units::dimensionless::scalar_t newKA)
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:6831
std::string ToString() const override
Definition Configs.hpp:6923
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:6643
constexpr Slot1Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:6886
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:6955
Gains for the specified slot.
Definition Configs.hpp:6994
std::string Serialize() const override
Definition Configs.hpp:7434
constexpr Slot2Configs & WithKG(units::dimensionless::scalar_t newKG)
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7351
constexpr Slot2Configs & WithKD(units::dimensionless::scalar_t newKD)
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7238
constexpr Slot2Configs & WithKS(units::dimensionless::scalar_t newKS)
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7271
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:7105
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:7138
constexpr Slot2Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:7381
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:7450
constexpr Slot2Configs & WithKI(units::dimensionless::scalar_t newKI)
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7208
constexpr Slot2Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:7410
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:7072
constexpr Slot2Configs & WithKP(units::dimensionless::scalar_t newKP)
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7179
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:7088
static Slot2Configs From(const SlotConfigs &value)
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:7050
constexpr Slot2Configs & WithKV(units::dimensionless::scalar_t newKV)
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7298
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:7013
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:7156
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:7031
std::string ToString() const override
Definition Configs.hpp:7418
constexpr Slot2Configs & WithKA(units::dimensionless::scalar_t newKA)
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7326
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:7119
Gains for the specified slot.
Definition Configs.hpp:7488
static SlotConfigs From(const Slot2Configs &value)
std::string ToString() const
Definition Configs.hpp:7972
constexpr SlotConfigs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:7927
static SlotConfigs From(const Slot1Configs &value)
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:7577
constexpr SlotConfigs & WithKS(units::dimensionless::scalar_t newKS)
Modifies this configuration's kS parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7817
constexpr SlotConfigs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:7956
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
Definition Configs.hpp:8005
constexpr SlotConfigs & WithKD(units::dimensionless::scalar_t newKD)
Modifies this configuration's kD parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7784
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:7702
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:7634
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:7618
constexpr SlotConfigs & WithKV(units::dimensionless::scalar_t newKV)
Modifies this configuration's kV parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7844
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:7559
constexpr SlotConfigs & WithKA(units::dimensionless::scalar_t newKA)
Modifies this configuration's kA parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7872
int SlotNumber
Chooses which slot these configs are for.
Definition Configs.hpp:7966
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:7596
constexpr SlotConfigs & WithKP(units::dimensionless::scalar_t newKP)
Modifies this configuration's kP parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7725
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:7651
std::string Serialize() const
Definition Configs.hpp:7988
static SlotConfigs From(const Slot0Configs &value)
constexpr SlotConfigs & WithKI(units::dimensionless::scalar_t newKI)
Modifies this configuration's kI parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7754
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:7684
constexpr SlotConfigs & WithKG(units::dimensionless::scalar_t newKG)
Modifies this configuration's kG parameter and returns itself for method-chaining and easier to use c...
Definition Configs.hpp:7897
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:7665
Configs that affect how software-limit switches behave.
Definition Configs.hpp:4127
units::angle::turn_t ReverseSoftLimitThreshold
Position threshold for reverse soft limit features.
Definition Configs.hpp:4164
std::string ToString() const override
Definition Configs.hpp:4246
constexpr SoftwareLimitSwitchConfigs & WithForwardSoftLimitThreshold(units::angle::turn_t newForwardSoftLimitThreshold)
Modifies this configuration's ForwardSoftLimitThreshold parameter and returns itself for method-chain...
Definition Configs.hpp:4217
units::angle::turn_t ForwardSoftLimitThreshold
Position threshold for forward soft limit features.
Definition Configs.hpp:4154
constexpr SoftwareLimitSwitchConfigs & WithReverseSoftLimitThreshold(units::angle::turn_t newReverseSoftLimitThreshold)
Modifies this configuration's ReverseSoftLimitThreshold parameter and returns itself for method-chain...
Definition Configs.hpp:4238
constexpr SoftwareLimitSwitchConfigs & WithReverseSoftLimitEnable(bool newReverseSoftLimitEnable)
Modifies this configuration's ReverseSoftLimitEnable parameter and returns itself for method-chaining...
Definition Configs.hpp:4196
std::string Serialize() const override
Definition Configs.hpp:4257
bool ReverseSoftLimitEnable
If enabled, the motor output is set to neutral if position exceeds ReverseSoftLimitThreshold and reve...
Definition Configs.hpp:4144
constexpr SoftwareLimitSwitchConfigs & WithForwardSoftLimitEnable(bool newForwardSoftLimitEnable)
Modifies this configuration's ForwardSoftLimitEnable parameter and returns itself for method-chaining...
Definition Configs.hpp:4178
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4268
bool ForwardSoftLimitEnable
If enabled, the motor output is set to neutral if position exceeds ForwardSoftLimitThreshold and forw...
Definition Configs.hpp:4137
Configs that affect the ToF sensor.
Definition Configs.hpp:4728
constexpr ToFParamsConfigs & WithUpdateFrequency(units::frequency::hertz_t newUpdateFrequency)
Modifies this configuration's UpdateFrequency parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:4783
std::string Serialize() const override
Definition Configs.hpp:4800
signals::UpdateModeValue UpdateMode
Update mode of the CANrange.
Definition Configs.hpp:4737
constexpr ToFParamsConfigs & WithUpdateMode(signals::UpdateModeValue newUpdateMode)
Modifies this configuration's UpdateMode parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:4761
units::frequency::hertz_t UpdateFrequency
Rate at which the CANrange will take measurements.
Definition Configs.hpp:4748
std::string ToString() const override
Definition Configs.hpp:4791
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4809
Configs that affect Torque Current control types.
Definition Configs.hpp:1342
std::string ToString() const override
Definition Configs.hpp:1440
units::current::ampere_t PeakReverseTorqueCurrent
Minimum (reverse) output during torque current based control modes.
Definition Configs.hpp:1365
units::current::ampere_t PeakForwardTorqueCurrent
Maximum (forward) output during torque current based control modes.
Definition Configs.hpp:1355
constexpr TorqueCurrentConfigs & WithPeakForwardTorqueCurrent(units::current::ampere_t newPeakForwardTorqueCurrent)
Modifies this configuration's PeakForwardTorqueCurrent parameter and returns itself for method-chaini...
Definition Configs.hpp:1391
constexpr TorqueCurrentConfigs & WithTorqueNeutralDeadband(units::current::ampere_t newTorqueNeutralDeadband)
Modifies this configuration's TorqueNeutralDeadband parameter and returns itself for method-chaining ...
Definition Configs.hpp:1432
units::current::ampere_t TorqueNeutralDeadband
Configures the output deadband during torque current based control modes.
Definition Configs.hpp:1375
constexpr TorqueCurrentConfigs & WithPeakReverseTorqueCurrent(units::current::ampere_t newPeakReverseTorqueCurrent)
Modifies this configuration's PeakReverseTorqueCurrent parameter and returns itself for method-chaini...
Definition Configs.hpp:1411
std::string Serialize() const override
Definition Configs.hpp:1450
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:1460
Configs that affect Voltage control types.
Definition Configs.hpp:1192
units::voltage::volt_t PeakForwardVoltage
Maximum (forward) output during voltage based control modes.
Definition Configs.hpp:1218
constexpr VoltageConfigs & WithPeakReverseVoltage(units::voltage::volt_t newPeakReverseVoltage)
Modifies this configuration's PeakReverseVoltage parameter and returns itself for method-chaining and...
Definition Configs.hpp:1288
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:1316
std::string Serialize() const override
Definition Configs.hpp:1306
std::string ToString() const override
Definition Configs.hpp:1296
units::time::second_t SupplyVoltageTimeConstant
The time constant (in seconds) of the low-pass filter for the supply voltage.
Definition Configs.hpp:1209
constexpr VoltageConfigs & WithPeakForwardVoltage(units::voltage::volt_t newPeakForwardVoltage)
Modifies this configuration's PeakForwardVoltage parameter and returns itself for method-chaining and...
Definition Configs.hpp:1268
constexpr VoltageConfigs & WithSupplyVoltageTimeConstant(units::time::second_t newSupplyVoltageTimeConstant)
Modifies this configuration's SupplyVoltageTimeConstant parameter and returns itself for method-chain...
Definition Configs.hpp:1248
units::voltage::volt_t PeakReverseVoltage
Minimum (reverse) output during voltage based control modes.
Definition Configs.hpp:1227
Class for CANcoder, a CAN based magnetic encoder that provides absolute and relative position along w...
Definition CoreCANcoder.hpp:631
Class for CTR Electronics' CANdi™ branded device, a device that integrates digital signals into the e...
Definition CoreCANdi.hpp:918
Class for CANrange, a CAN based Time of Flight (ToF) sensor that measures the distance to the front o...
Definition CoreCANrange.hpp:728
Class description for the Talon FX integrated motor controller.
Definition CoreTalonFX.hpp:2932
Requires Phoenix Pro; Improves commutation and velocity measurement for motors with hall sensors.
Definition SpnEnums.hpp:3764
static constexpr int Disabled
Talon will utilize hall sensors without advanced features.
Definition SpnEnums.hpp:3771
If a brushed motor is selected with Motor Arrangement, this config determines which of three leads to...
Definition SpnEnums.hpp:4905
int value
Definition SpnEnums.hpp:4907
static constexpr int Leads_A_and_B
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:4920
Choose what sensor source is used for differential control of a mechanism.
Definition SpnEnums.hpp:3240
static constexpr int Disabled
Disable differential control.
Definition SpnEnums.hpp:3247
Choose what sensor source is reported via API and used by closed-loop and limit features.
Definition SpnEnums.hpp:4392
static constexpr int Commutation
Use the external sensor used for motor commutation.
Definition SpnEnums.hpp:4399
Choose what sensor source is reported via API and used by closed-loop and limit features.
Definition SpnEnums.hpp:2411
static constexpr int RotorSensor
Use the internal rotor sensor in the Talon.
Definition SpnEnums.hpp:2418
Determines where to poll the forward limit switch.
Definition SpnEnums.hpp:2703
static constexpr int LimitSwitchPin
Use the forward limit switch pin on the limit switch connector.
Definition SpnEnums.hpp:2710
int value
Definition SpnEnums.hpp:2705
Determines if the forward limit switch is normally-open (default) or normally-closed.
Definition SpnEnums.hpp:2616
static constexpr int NormallyOpen
Definition SpnEnums.hpp:2620
int value
Definition SpnEnums.hpp:2618
Gravity Feedforward/Feedback Type.
Definition SpnEnums.hpp:2138
static constexpr int Elevator_Static
The system's gravity feedforward is constant, such as an elevator.
Definition SpnEnums.hpp:2146
int value
Definition SpnEnums.hpp:2140
Invert state of the device as seen from the front of the motor.
Definition SpnEnums.hpp:2223
static constexpr int CounterClockwise_Positive
Positive motor output results in counter-clockwise motion.
Definition SpnEnums.hpp:2230
int value
Definition SpnEnums.hpp:2225
Selects the motor and motor connections used with Talon.
Definition SpnEnums.hpp:3853
int value
Definition SpnEnums.hpp:3855
static constexpr int Disabled
Motor is not selected.
Definition SpnEnums.hpp:3862
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2303
int value
Definition SpnEnums.hpp:2305
static constexpr int Coast
Definition SpnEnums.hpp:2307
Determines where to poll the reverse limit switch.
Definition SpnEnums.hpp:2913
int value
Definition SpnEnums.hpp:2915
static constexpr int LimitSwitchPin
Use the reverse limit switch pin on the limit switch connector.
Definition SpnEnums.hpp:2920
Determines if the reverse limit switch is normally-open (default) or normally-closed.
Definition SpnEnums.hpp:2826
static constexpr int NormallyOpen
Definition SpnEnums.hpp:2830
int value
Definition SpnEnums.hpp:2828
What value the Signal 1 input (S1IN) needs to be for the CTR Electronics' CANdi™ to detect as Closed.
Definition SpnEnums.hpp:4702
int value
Definition SpnEnums.hpp:4704
static constexpr int CloseWhenNotFloating
The S1 input will be treated as closed when it is not floating.
Definition SpnEnums.hpp:4709
The floating state of the Signal 1 input (S1IN).
Definition SpnEnums.hpp:4162
int value
Definition SpnEnums.hpp:4164
static constexpr int FloatDetect
The input will attempt to detect when it is floating.
Definition SpnEnums.hpp:4170
What value the Signal 2 input (S2IN) needs to be for the CTR Electronics' CANdi™ to detect as Closed.
Definition SpnEnums.hpp:4805
int value
Definition SpnEnums.hpp:4807
static constexpr int CloseWhenNotFloating
The S2 input will be treated as closed when it is not floating.
Definition SpnEnums.hpp:4812
The floating state of the Signal 2 input (S2IN).
Definition SpnEnums.hpp:4255
int value
Definition SpnEnums.hpp:4257
static constexpr int FloatDetect
The input will attempt to detect when it is floating.
Definition SpnEnums.hpp:4263
Direction of the sensor to determine positive rotation, as seen facing the LED side of the CANcoder.
Definition SpnEnums.hpp:270
static constexpr int CounterClockwise_Positive
Counter-clockwise motion reports positive rotation.
Definition SpnEnums.hpp:277
int value
Definition SpnEnums.hpp:272
The relationship between the motor controlled by a Talon and the external sensor connected to the dat...
Definition SpnEnums.hpp:4619
int value
Definition SpnEnums.hpp:4621
static constexpr int Aligned
The sensor direction is normally aligned with the motor.
Definition SpnEnums.hpp:4626
Static Feedforward Sign during position closed loop.
Definition SpnEnums.hpp:3370
static constexpr int UseVelocitySign
Use the velocity reference sign.
Definition SpnEnums.hpp:3379
Update mode of the CANrange.
Definition SpnEnums.hpp:3674
int value
Definition SpnEnums.hpp:3676
static constexpr int ShortRange100Hz
Updates distance/proximity at 100hz using short-range detection mode.
Definition SpnEnums.hpp:3681
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18