CTRE Phoenix 6 C++ 25.3.1
Loading...
Searching...
No Matches
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 Remote
1839 * CANdi PWM 1 by passing in the CANdi object.
1840 *
1841 * \param device CANdi reference to use for Remote CANdi
1842 * \returns Itself
1843 */
1845
1846 /**
1847 * \brief Helper method to configure this feedback group to use Remote
1848 * CANdi PWM 2 by passing in the CANdi object.
1849 *
1850 * \param device CANdi reference to use for Remote CANdi
1851 * \returns Itself
1852 */
1854
1855 /**
1856 * \brief Helper method to configure this feedback group to use Remote
1857 * CANdi Quadrature by passing in the CANdi object.
1858 *
1859 * \param device CANdi reference to use for Remote CANdi
1860 * \returns Itself
1861 */
1863
1864 /**
1865 * \brief Helper method to configure this feedback group to use Fused
1866 * CANdi PWM 1 by passing in the CANdi object.
1867 *
1868 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1869 * fuse another CANdi's information with the internal rotor,
1870 * which provides the best possible position and velocity for
1871 * accuracy and bandwidth.
1872 *
1873 * \param device CANdi reference to use for Fused CANdi
1874 * \returns Itself
1875 */
1877
1878 /**
1879 * \brief Helper method to configure this feedback group to use Fused
1880 * CANdi PWM 2 by passing in the CANdi object.
1881 *
1882 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1883 * fuse another CANdi's information with the internal rotor,
1884 * which provides the best possible position and velocity for
1885 * accuracy and bandwidth.
1886 *
1887 * \param device CANdi reference to use for Fused CANdi
1888 * \returns Itself
1889 */
1891
1892 /**
1893 * \brief Helper method to configure this feedback group to use Fused
1894 * CANdi Quadrature by passing in the CANdi object.
1895 *
1896 * When using FusedCANdi (requires Phoenix Pro), the Talon will
1897 * fuse another CANdi's information with the internal rotor,
1898 * which provides the best possible position and velocity for
1899 * accuracy and bandwidth.
1900 *
1901 * \param device CANdi reference to use for Fused CANdi
1902 * \returns Itself
1903 */
1905
1906 /**
1907 * \brief Helper method to configure this feedback group to use Sync
1908 * CANdi 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, then continue to use the rotor sensor for closed loop
1913 * control. The Talon will report if its internal position
1914 * differs significantly from the reported CANdi position.
1915 * SyncCANdi was developed for mechanisms where there is a risk
1916 * of the CANdi failing in such a way that it reports a
1917 * position that does not match the mechanism, such as the
1918 * sensor mounting assembly breaking off.
1919 *
1920 * \param device CANdi reference to use for Sync CANdi
1921 * \returns Itself
1922 */
1924
1925 /**
1926 * \brief Helper method to configure this feedback group to use Sync
1927 * CANdi PWM 2 by passing in the CANdi object.
1928 *
1929 * When using SyncCANdi (requires Phoenix Pro), the Talon will
1930 * synchronize its internal rotor position against another
1931 * CANdi, then continue to use the rotor sensor for closed loop
1932 * control. The Talon will report if its internal position
1933 * differs significantly from the reported CANdi position.
1934 * SyncCANdi was developed for mechanisms where there is a risk
1935 * of the CANdi failing in such a way that it reports a
1936 * position that does not match the mechanism, such as the
1937 * sensor mounting assembly breaking off.
1938 *
1939 * \param device CANdi reference to use for Sync CANdi
1940 * \returns Itself
1941 */
1943
1944
1945
1946 std::string ToString() const override
1947 {
1948 std::stringstream ss;
1949 ss << "Config Group: Feedback" << std::endl;
1950 ss << " FeedbackRotorOffset: " << FeedbackRotorOffset.to<double>() << " rotations" << std::endl;
1951 ss << " SensorToMechanismRatio: " << SensorToMechanismRatio.to<double>() << " scalar" << std::endl;
1952 ss << " RotorToSensorRatio: " << RotorToSensorRatio.to<double>() << " scalar" << std::endl;
1953 ss << " FeedbackSensorSource: " << FeedbackSensorSource << std::endl;
1954 ss << " FeedbackRemoteSensorID: " << FeedbackRemoteSensorID << std::endl;
1955 ss << " VelocityFilterTimeConstant: " << VelocityFilterTimeConstant.to<double>() << " seconds" << std::endl;
1956 return ss.str();
1957 }
1958
1959 std::string Serialize() const override
1960 {
1961 std::stringstream ss;
1962 char *ref;
1963 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_FeedbackRotorOffset, FeedbackRotorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1964 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, SensorToMechanismRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1965 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, RotorToSensorRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1966 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackSensorSource, FeedbackSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1967 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, FeedbackRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
1968 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, VelocityFilterTimeConstant.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
1969 return ss.str();
1970 }
1971
1972 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
1973 {
1974 const char *string_c_str = to_deserialize.c_str();
1975 size_t string_length = to_deserialize.length();
1976 double FeedbackRotorOffsetVal = FeedbackRotorOffset.to<double>();
1977 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_FeedbackRotorOffset, string_c_str, string_length, &FeedbackRotorOffsetVal);
1978 FeedbackRotorOffset = units::angle::turn_t{FeedbackRotorOffsetVal};
1979 double SensorToMechanismRatioVal = SensorToMechanismRatio.to<double>();
1980 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, string_c_str, string_length, &SensorToMechanismRatioVal);
1981 SensorToMechanismRatio = units::dimensionless::scalar_t{SensorToMechanismRatioVal};
1982 double RotorToSensorRatioVal = RotorToSensorRatio.to<double>();
1983 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, string_c_str, string_length, &RotorToSensorRatioVal);
1984 RotorToSensorRatio = units::dimensionless::scalar_t{RotorToSensorRatioVal};
1985 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackSensorSource, string_c_str, string_length, &FeedbackSensorSource.value);
1986 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, string_c_str, string_length, &FeedbackRemoteSensorID);
1987 double VelocityFilterTimeConstantVal = VelocityFilterTimeConstant.to<double>();
1988 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, string_c_str, string_length, &VelocityFilterTimeConstantVal);
1989 VelocityFilterTimeConstant = units::time::second_t{VelocityFilterTimeConstantVal};
1990 return 0;
1991 }
1992};
1993
1994
1995/**
1996 * \brief Configs that affect the external feedback sensor of this
1997 * motor controller.
1998 *
1999 * \details Includes feedback sensor source, offsets and sensor phase
2000 * for the feedback sensor, and various ratios to describe
2001 * the relationship between the sensor and the mechanism for
2002 * closed looping.
2003 */
2005{
2006public:
2007 constexpr ExternalFeedbackConfigs() = default;
2008
2009 /**
2010 * \brief The ratio of sensor rotations to the mechanism's output,
2011 * where a ratio greater than 1 is a reduction.
2012 *
2013 * This is equivalent to the mechanism's gear ratio if the sensor is
2014 * located on the input of a gearbox. If sensor is on the output of a
2015 * gearbox, then this is typically set to 1.
2016 *
2017 * We recommend against using this config to perform onboard unit
2018 * conversions. Instead, unit conversions should be performed in
2019 * robot code using the units library.
2020 *
2021 * If this is set to zero, the device will reset back to one.
2022 *
2023 * - Minimum Value: -1000
2024 * - Maximum Value: 1000
2025 * - Default Value: 1.0
2026 * - Units: scalar
2027 */
2028 units::dimensionless::scalar_t SensorToMechanismRatio = 1.0;
2029 /**
2030 * \brief The ratio of motor rotor rotations to remote sensor
2031 * rotations, where a ratio greater than 1 is a reduction.
2032 *
2033 * The Talon FX is capable of fusing a remote CANcoder with its rotor
2034 * sensor to produce a high-bandwidth sensor source. This feature
2035 * requires specifying the ratio between the motor rotor and the
2036 * remote sensor.
2037 *
2038 * If this is set to zero, the device will reset back to one.
2039 *
2040 * - Minimum Value: -1000
2041 * - Maximum Value: 1000
2042 * - Default Value: 1.0
2043 * - Units: scalar
2044 */
2045 units::dimensionless::scalar_t RotorToSensorRatio = 1.0;
2046 /**
2047 * \brief Device ID of which remote device to use. This is not used
2048 * if the Sensor Source is the internal rotor sensor.
2049 *
2050 * - Minimum Value: 0
2051 * - Maximum Value: 62
2052 * - Default Value: 0
2053 * - Units:
2054 */
2056 /**
2057 * \brief The configurable time constant of the Kalman velocity
2058 * filter. The velocity Kalman filter will adjust to act as a low-pass
2059 * with this value as its time constant.
2060 *
2061 * \details If the user is aiming for an expected cutoff frequency,
2062 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
2063 * time constant.
2064 *
2065 * - Minimum Value: 0
2066 * - Maximum Value: 1
2067 * - Default Value: 0
2068 * - Units: seconds
2069 */
2070 units::time::second_t VelocityFilterTimeConstant = 0_s;
2071 /**
2072 * \brief The offset applied to any absolute sensor connected to the
2073 * Talon data port. This is only supported when using the PulseWidth
2074 * sensor source.
2075 *
2076 * This can be used to zero the sensor position in applications where
2077 * the sensor is 1:1 with the mechanism.
2078 *
2079 * - Minimum Value: -1
2080 * - Maximum Value: 1
2081 * - Default Value: 0.0
2082 * - Units: rotations
2083 */
2084 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
2085 /**
2086 * \brief Choose what sensor source is reported via API and used by
2087 * closed-loop and limit features. The default is Commutation, which
2088 * uses the external sensor used for motor commutation.
2089 *
2090 * Choose Remote* to use another sensor on the same CAN bus (this also
2091 * requires setting FeedbackRemoteSensorID). Talon will update its
2092 * position and velocity whenever the remote sensor publishes its
2093 * information on CAN bus, and the Talon commutation sensor will not
2094 * be used.
2095 *
2096 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
2097 * sensor's information with the commutation sensor, which provides
2098 * the best possible position and velocity for accuracy and bandwidth
2099 * (this also requires setting FeedbackRemoteSensorID). This was
2100 * developed for applications such as swerve-azimuth.
2101 *
2102 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
2103 * commutation sensor position against another sensor, then continue
2104 * to use the rotor sensor for closed loop control (this also requires
2105 * setting FeedbackRemoteSensorID). The Talon will report if its
2106 * internal position differs significantly from the reported remote
2107 * sensor position. This was developed for mechanisms where there is
2108 * a risk of the sensor failing in such a way that it reports a
2109 * position that does not match the mechanism, such as the sensor
2110 * mounting assembly breaking off.
2111 *
2112 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2113 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2114 * also requires setting FeedbackRemoteSensorID). Talon will update
2115 * its position to match the selected value whenever Pigeon2 publishes
2116 * its information on CAN bus. Note that the Talon position will be in
2117 * rotations and not degrees.
2118 *
2119 * Choose Quadrature to use a quadrature encoder directly attached to
2120 * the Talon data port. This provides velocity and relative position
2121 * measurements.
2122 *
2123 * Choose PulseWidth to use a pulse-width encoder directly attached to
2124 * the Talon data port. This provides velocity and absolute position
2125 * measurements.
2126 *
2127 * \details Note: When the feedback source is changed to Fused* or
2128 * Sync*, the Talon needs a period of time to fuse before sensor-based
2129 * (soft-limit, closed loop, etc.) features are used. This period of
2130 * time is determined by the update frequency of the remote sensor's
2131 * Position signal.
2132 *
2133 */
2135 /**
2136 * \brief The relationship between the motor controlled by a Talon and
2137 * the external sensor connected to the data port. This does not
2138 * affect the commutation sensor or remote sensors.
2139 *
2140 * To determine the sensor phase, set this config to Aligned and drive
2141 * the motor with positive output. If the reported sensor velocity is
2142 * positive, then the phase is Aligned. If the reported sensor
2143 * velocity is negative, then the phase is Opposed.
2144 *
2145 * The sensor direction is automatically inverted along with motor
2146 * invert, so the sensor phase does not need to be changed when motor
2147 * invert changes.
2148 *
2149 */
2151 /**
2152 * \brief The number of quadrature edges in one rotation for the
2153 * quadrature sensor connected to the Talon data port.
2154 *
2155 * This is the total number of transitions from high-to-low or
2156 * low-to-high across both channels per rotation of the sensor. This
2157 * is also equivalent to the Counts Per Revolution when using 4x
2158 * decoding.
2159 *
2160 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
2161 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
2162 * 4096 edges per rotation.
2163 *
2164 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
2165 * RPM.
2166 *
2167 * - Minimum Value: 1
2168 * - Maximum Value: 1000000
2169 * - Default Value: 4096
2170 * - Units:
2171 */
2173 /**
2174 * \brief The positive discontinuity point of the absolute sensor in
2175 * rotations. This determines the point at which the absolute sensor
2176 * wraps around, keeping the absolute position in the range [x-1, x).
2177 *
2178 * - Setting this to 1 makes the absolute position unsigned [0, 1)
2179 * - Setting this to 0.5 makes the absolute position signed [-0.5,
2180 * 0.5)
2181 * - Setting this to 0 makes the absolute position always negative
2182 * [-1, 0)
2183 *
2184 * Many rotational mechanisms such as arms have a region of motion
2185 * that is unreachable. This should be set to the center of that
2186 * region of motion, in non-negative rotations. This affects the
2187 * position of the device at bootup.
2188 *
2189 * \details For example, consider an arm which can travel from -0.2 to
2190 * 0.6 rotations with a little leeway, where 0 is horizontally
2191 * forward. Since -0.2 rotations has the same absolute position as 0.8
2192 * rotations, we can say that the arm typically does not travel in the
2193 * range (0.6, 0.8) rotations. As a result, the discontinuity point
2194 * would be the center of that range, which is 0.7 rotations. This
2195 * results in an absolute sensor range of [-0.3, 0.7) rotations.
2196 *
2197 * On a Talon motor controller, this is only supported when using the
2198 * PulseWidth sensor source.
2199 *
2200 * - Minimum Value: 0.0
2201 * - Maximum Value: 1.0
2202 * - Default Value: 0.5
2203 * - Units: rotations
2204 */
2205 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
2206
2207 /**
2208 * \brief Modifies this configuration's SensorToMechanismRatio parameter and returns itself for
2209 * method-chaining and easier to use config API.
2210 *
2211 * The ratio of sensor rotations to the mechanism's output, where a
2212 * ratio greater than 1 is a reduction.
2213 *
2214 * This is equivalent to the mechanism's gear ratio if the sensor is
2215 * located on the input of a gearbox. If sensor is on the output of a
2216 * gearbox, then this is typically set to 1.
2217 *
2218 * We recommend against using this config to perform onboard unit
2219 * conversions. Instead, unit conversions should be performed in
2220 * robot code using the units library.
2221 *
2222 * If this is set to zero, the device will reset back to one.
2223 *
2224 * - Minimum Value: -1000
2225 * - Maximum Value: 1000
2226 * - Default Value: 1.0
2227 * - Units: scalar
2228 *
2229 * \param newSensorToMechanismRatio Parameter to modify
2230 * \returns Itself
2231 */
2232 constexpr ExternalFeedbackConfigs &WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
2233 {
2234 SensorToMechanismRatio = std::move(newSensorToMechanismRatio);
2235 return *this;
2236 }
2237
2238 /**
2239 * \brief Modifies this configuration's RotorToSensorRatio parameter and returns itself for
2240 * method-chaining and easier to use config API.
2241 *
2242 * The ratio of motor rotor rotations to remote sensor rotations,
2243 * where a ratio greater than 1 is a reduction.
2244 *
2245 * The Talon FX is capable of fusing a remote CANcoder with its rotor
2246 * sensor to produce a high-bandwidth sensor source. This feature
2247 * requires specifying the ratio between the motor rotor and the
2248 * remote sensor.
2249 *
2250 * If this is set to zero, the device will reset back to one.
2251 *
2252 * - Minimum Value: -1000
2253 * - Maximum Value: 1000
2254 * - Default Value: 1.0
2255 * - Units: scalar
2256 *
2257 * \param newRotorToSensorRatio Parameter to modify
2258 * \returns Itself
2259 */
2260 constexpr ExternalFeedbackConfigs &WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
2261 {
2262 RotorToSensorRatio = std::move(newRotorToSensorRatio);
2263 return *this;
2264 }
2265
2266 /**
2267 * \brief Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for
2268 * method-chaining and easier to use config API.
2269 *
2270 * Device ID of which remote device to use. This is not used if the
2271 * Sensor Source is the internal rotor sensor.
2272 *
2273 * - Minimum Value: 0
2274 * - Maximum Value: 62
2275 * - Default Value: 0
2276 * - Units:
2277 *
2278 * \param newFeedbackRemoteSensorID Parameter to modify
2279 * \returns Itself
2280 */
2281 constexpr ExternalFeedbackConfigs &WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
2282 {
2283 FeedbackRemoteSensorID = std::move(newFeedbackRemoteSensorID);
2284 return *this;
2285 }
2286
2287 /**
2288 * \brief Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for
2289 * method-chaining and easier to use config API.
2290 *
2291 * The configurable time constant of the Kalman velocity filter. The
2292 * velocity Kalman filter will adjust to act as a low-pass with this
2293 * value as its time constant.
2294 *
2295 * \details If the user is aiming for an expected cutoff frequency,
2296 * the frequency is calculated as 1 / (2 * π * τ) with τ being the
2297 * time constant.
2298 *
2299 * - Minimum Value: 0
2300 * - Maximum Value: 1
2301 * - Default Value: 0
2302 * - Units: seconds
2303 *
2304 * \param newVelocityFilterTimeConstant Parameter to modify
2305 * \returns Itself
2306 */
2307 constexpr ExternalFeedbackConfigs &WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
2308 {
2309 VelocityFilterTimeConstant = std::move(newVelocityFilterTimeConstant);
2310 return *this;
2311 }
2312
2313 /**
2314 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
2315 * method-chaining and easier to use config API.
2316 *
2317 * The offset applied to any absolute sensor connected to the Talon
2318 * data port. This is only supported when using the PulseWidth sensor
2319 * source.
2320 *
2321 * This can be used to zero the sensor position in applications where
2322 * the sensor is 1:1 with the mechanism.
2323 *
2324 * - Minimum Value: -1
2325 * - Maximum Value: 1
2326 * - Default Value: 0.0
2327 * - Units: rotations
2328 *
2329 * \param newAbsoluteSensorOffset Parameter to modify
2330 * \returns Itself
2331 */
2332 constexpr ExternalFeedbackConfigs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
2333 {
2334 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
2335 return *this;
2336 }
2337
2338 /**
2339 * \brief Modifies this configuration's ExternalFeedbackSensorSource parameter and returns itself for
2340 * method-chaining and easier to use config API.
2341 *
2342 * Choose what sensor source is reported via API and used by
2343 * closed-loop and limit features. The default is Commutation, which
2344 * uses the external sensor used for motor commutation.
2345 *
2346 * Choose Remote* to use another sensor on the same CAN bus (this also
2347 * requires setting FeedbackRemoteSensorID). Talon will update its
2348 * position and velocity whenever the remote sensor publishes its
2349 * information on CAN bus, and the Talon commutation sensor will not
2350 * be used.
2351 *
2352 * Choose Fused* (requires Phoenix Pro) and Talon will fuse another
2353 * sensor's information with the commutation sensor, which provides
2354 * the best possible position and velocity for accuracy and bandwidth
2355 * (this also requires setting FeedbackRemoteSensorID). This was
2356 * developed for applications such as swerve-azimuth.
2357 *
2358 * Choose Sync* (requires Phoenix Pro) and Talon will synchronize its
2359 * commutation sensor position against another sensor, then continue
2360 * to use the rotor sensor for closed loop control (this also requires
2361 * setting FeedbackRemoteSensorID). The Talon will report if its
2362 * internal position differs significantly from the reported remote
2363 * sensor position. This was developed for mechanisms where there is
2364 * a risk of the sensor failing in such a way that it reports a
2365 * position that does not match the mechanism, such as the sensor
2366 * mounting assembly breaking off.
2367 *
2368 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2369 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2370 * also requires setting FeedbackRemoteSensorID). Talon will update
2371 * its position to match the selected value whenever Pigeon2 publishes
2372 * its information on CAN bus. Note that the Talon position will be in
2373 * rotations and not degrees.
2374 *
2375 * Choose Quadrature to use a quadrature encoder directly attached to
2376 * the Talon data port. This provides velocity and relative position
2377 * measurements.
2378 *
2379 * Choose PulseWidth to use a pulse-width encoder directly attached to
2380 * the Talon data port. This provides velocity and absolute position
2381 * measurements.
2382 *
2383 * \details Note: When the feedback source is changed to Fused* or
2384 * Sync*, the Talon needs a period of time to fuse before sensor-based
2385 * (soft-limit, closed loop, etc.) features are used. This period of
2386 * time is determined by the update frequency of the remote sensor's
2387 * Position signal.
2388 *
2389 *
2390 * \param newExternalFeedbackSensorSource Parameter to modify
2391 * \returns Itself
2392 */
2394 {
2395 ExternalFeedbackSensorSource = std::move(newExternalFeedbackSensorSource);
2396 return *this;
2397 }
2398
2399 /**
2400 * \brief Modifies this configuration's SensorPhase parameter and returns itself for
2401 * method-chaining and easier to use config API.
2402 *
2403 * The relationship between the motor controlled by a Talon and the
2404 * external sensor connected to the data port. This does not affect
2405 * the commutation sensor or remote sensors.
2406 *
2407 * To determine the sensor phase, set this config to Aligned and drive
2408 * the motor with positive output. If the reported sensor velocity is
2409 * positive, then the phase is Aligned. If the reported sensor
2410 * velocity is negative, then the phase is Opposed.
2411 *
2412 * The sensor direction is automatically inverted along with motor
2413 * invert, so the sensor phase does not need to be changed when motor
2414 * invert changes.
2415 *
2416 *
2417 * \param newSensorPhase Parameter to modify
2418 * \returns Itself
2419 */
2421 {
2422 SensorPhase = std::move(newSensorPhase);
2423 return *this;
2424 }
2425
2426 /**
2427 * \brief Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for
2428 * method-chaining and easier to use config API.
2429 *
2430 * The number of quadrature edges in one rotation for the quadrature
2431 * sensor connected to the Talon data port.
2432 *
2433 * This is the total number of transitions from high-to-low or
2434 * low-to-high across both channels per rotation of the sensor. This
2435 * is also equivalent to the Counts Per Revolution when using 4x
2436 * decoding.
2437 *
2438 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
2439 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
2440 * 4096 edges per rotation.
2441 *
2442 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
2443 * RPM.
2444 *
2445 * - Minimum Value: 1
2446 * - Maximum Value: 1000000
2447 * - Default Value: 4096
2448 * - Units:
2449 *
2450 * \param newQuadratureEdgesPerRotation Parameter to modify
2451 * \returns Itself
2452 */
2453 constexpr ExternalFeedbackConfigs &WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
2454 {
2455 QuadratureEdgesPerRotation = std::move(newQuadratureEdgesPerRotation);
2456 return *this;
2457 }
2458
2459 /**
2460 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
2461 * method-chaining and easier to use config API.
2462 *
2463 * The positive discontinuity point of the absolute sensor in
2464 * rotations. This determines the point at which the absolute sensor
2465 * wraps around, keeping the absolute position in the range [x-1, x).
2466 *
2467 * - Setting this to 1 makes the absolute position unsigned [0, 1)
2468 * - Setting this to 0.5 makes the absolute position signed [-0.5,
2469 * 0.5)
2470 * - Setting this to 0 makes the absolute position always negative
2471 * [-1, 0)
2472 *
2473 * Many rotational mechanisms such as arms have a region of motion
2474 * that is unreachable. This should be set to the center of that
2475 * region of motion, in non-negative rotations. This affects the
2476 * position of the device at bootup.
2477 *
2478 * \details For example, consider an arm which can travel from -0.2 to
2479 * 0.6 rotations with a little leeway, where 0 is horizontally
2480 * forward. Since -0.2 rotations has the same absolute position as 0.8
2481 * rotations, we can say that the arm typically does not travel in the
2482 * range (0.6, 0.8) rotations. As a result, the discontinuity point
2483 * would be the center of that range, which is 0.7 rotations. This
2484 * results in an absolute sensor range of [-0.3, 0.7) rotations.
2485 *
2486 * On a Talon motor controller, this is only supported when using the
2487 * PulseWidth sensor source.
2488 *
2489 * - Minimum Value: 0.0
2490 * - Maximum Value: 1.0
2491 * - Default Value: 0.5
2492 * - Units: rotations
2493 *
2494 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
2495 * \returns Itself
2496 */
2497 constexpr ExternalFeedbackConfigs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
2498 {
2499 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
2500 return *this;
2501 }
2502
2503 /**
2504 * \brief Helper method to configure this feedback group to use
2505 * RemoteCANcoder by passing in the CANcoder object.
2506 *
2507 * When using RemoteCANcoder, the Talon will use another
2508 * CANcoder on the same CAN bus. The Talon will update its
2509 * position and velocity whenever CANcoder publishes its
2510 * information on CAN bus, and the Talon commutation sensor
2511 * will not be used.
2512 *
2513 * \param device CANcoder reference to use for RemoteCANcoder
2514 * \returns Itself
2515 */
2517
2518 /**
2519 * \brief Helper method to configure this feedback group to use
2520 * FusedCANcoder by passing in the CANcoder object.
2521 *
2522 * When using FusedCANcoder (requires Phoenix Pro), the Talon
2523 * will fuse another CANcoder's information with the
2524 * commutation sensor, which provides the best possible
2525 * position and velocity for accuracy and bandwidth.
2526 * FusedCANcoder was developed for applications such as
2527 * swerve-azimuth.
2528 *
2529 * \param device CANcoder reference to use for FusedCANcoder
2530 * \returns Itself
2531 */
2533
2534 /**
2535 * \brief Helper method to configure this feedback group to use
2536 * SyncCANcoder by passing in the CANcoder object.
2537 *
2538 * When using SyncCANcoder (requires Phoenix Pro), the Talon
2539 * will synchronize its commutation sensor position against
2540 * another CANcoder, then continue to use the rotor sensor for
2541 * closed loop control. The Talon will report if its internal
2542 * position differs significantly from the reported CANcoder
2543 * position. SyncCANcoder was developed for mechanisms where
2544 * there is a risk of the CANcoder failing in such a way that
2545 * it reports a position that does not match the mechanism,
2546 * such as the sensor mounting assembly breaking off.
2547 *
2548 * \param device CANcoder reference to use for SyncCANcoder
2549 * \returns Itself
2550 */
2552
2553 /**
2554 * \brief Helper method to configure this feedback group to use Remote
2555 * CANdi PWM 1 by passing in the CANdi object.
2556 *
2557 * \param device CANdi reference to use for Remote CANdi
2558 * \returns Itself
2559 */
2561
2562 /**
2563 * \brief Helper method to configure this feedback group to use Remote
2564 * CANdi PWM 2 by passing in the CANdi object.
2565 *
2566 * \param device CANdi reference to use for Remote CANdi
2567 * \returns Itself
2568 */
2570
2571 /**
2572 * \brief Helper method to configure this feedback group to use Remote
2573 * CANdi Quadrature by passing in the CANdi object.
2574 *
2575 * \param device CANdi reference to use for Remote CANdi
2576 * \returns Itself
2577 */
2579
2580 /**
2581 * \brief Helper method to configure this feedback group to use Fused
2582 * CANdi PWM 1 by passing in the CANdi object.
2583 *
2584 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2585 * fuse another CANdi's information with the internal rotor,
2586 * which provides the best possible position and velocity for
2587 * accuracy and bandwidth.
2588 *
2589 * \param device CANdi reference to use for Fused CANdi
2590 * \returns Itself
2591 */
2593
2594 /**
2595 * \brief Helper method to configure this feedback group to use Fused
2596 * CANdi PWM 2 by passing in the CANdi object.
2597 *
2598 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2599 * fuse another CANdi's information with the internal rotor,
2600 * which provides the best possible position and velocity for
2601 * accuracy and bandwidth.
2602 *
2603 * \param device CANdi reference to use for Fused CANdi
2604 * \returns Itself
2605 */
2607
2608 /**
2609 * \brief Helper method to configure this feedback group to use Fused
2610 * CANdi Quadrature by passing in the CANdi object.
2611 *
2612 * When using FusedCANdi (requires Phoenix Pro), the Talon will
2613 * fuse another CANdi's information with the internal rotor,
2614 * which provides the best possible position and velocity for
2615 * accuracy and bandwidth.
2616 *
2617 * \param device CANdi reference to use for Fused CANdi
2618 * \returns Itself
2619 */
2621
2622 /**
2623 * \brief Helper method to configure this feedback group to use Sync
2624 * CANdi PWM 1 by passing in the CANdi object.
2625 *
2626 * When using SyncCANdi (requires Phoenix Pro), the Talon will
2627 * synchronize its internal rotor position against another
2628 * CANdi, then continue to use the rotor sensor for closed loop
2629 * control. The Talon will report if its internal position
2630 * differs significantly from the reported CANdi position.
2631 * SyncCANdi was developed for mechanisms where there is a risk
2632 * of the CANdi failing in such a way that it reports a
2633 * position that does not match the mechanism, such as the
2634 * sensor mounting assembly breaking off.
2635 *
2636 * \param device CANdi reference to use for Sync CANdi
2637 * \returns Itself
2638 */
2640
2641 /**
2642 * \brief Helper method to configure this feedback group to use Sync
2643 * CANdi PWM 2 by passing in the CANdi object.
2644 *
2645 * When using SyncCANdi (requires Phoenix Pro), the Talon will
2646 * synchronize its internal rotor position against another
2647 * CANdi, then continue to use the rotor sensor for closed loop
2648 * control. The Talon will report if its internal position
2649 * differs significantly from the reported CANdi position.
2650 * SyncCANdi was developed for mechanisms where there is a risk
2651 * of the CANdi failing in such a way that it reports a
2652 * position that does not match the mechanism, such as the
2653 * sensor mounting assembly breaking off.
2654 *
2655 * \param device CANdi reference to use for Sync CANdi
2656 * \returns Itself
2657 */
2659
2660
2661
2662 std::string ToString() const override
2663 {
2664 std::stringstream ss;
2665 ss << "Config Group: ExternalFeedback" << std::endl;
2666 ss << " SensorToMechanismRatio: " << SensorToMechanismRatio.to<double>() << " scalar" << std::endl;
2667 ss << " RotorToSensorRatio: " << RotorToSensorRatio.to<double>() << " scalar" << std::endl;
2668 ss << " FeedbackRemoteSensorID: " << FeedbackRemoteSensorID << std::endl;
2669 ss << " VelocityFilterTimeConstant: " << VelocityFilterTimeConstant.to<double>() << " seconds" << std::endl;
2670 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
2671 ss << " ExternalFeedbackSensorSource: " << ExternalFeedbackSensorSource << std::endl;
2672 ss << " SensorPhase: " << SensorPhase << std::endl;
2673 ss << " QuadratureEdgesPerRotation: " << QuadratureEdgesPerRotation << std::endl;
2674 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
2675 return ss.str();
2676 }
2677
2678 std::string Serialize() const override
2679 {
2680 std::stringstream ss;
2681 char *ref;
2682 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, SensorToMechanismRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2683 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, RotorToSensorRatio.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2684 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, FeedbackRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2685 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, VelocityFilterTimeConstant.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2686 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2687 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ExternalFeedbackSensorSource, ExternalFeedbackSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2688 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_SensorPhase, SensorPhase.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2689 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, QuadratureEdgesPerRotation, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2690 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
2691 return ss.str();
2692 }
2693
2694 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
2695 {
2696 const char *string_c_str = to_deserialize.c_str();
2697 size_t string_length = to_deserialize.length();
2698 double SensorToMechanismRatioVal = SensorToMechanismRatio.to<double>();
2699 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_SensorToMechanismRatio, string_c_str, string_length, &SensorToMechanismRatioVal);
2700 SensorToMechanismRatio = units::dimensionless::scalar_t{SensorToMechanismRatioVal};
2701 double RotorToSensorRatioVal = RotorToSensorRatio.to<double>();
2702 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_RotorToSensorRatio, string_c_str, string_length, &RotorToSensorRatioVal);
2703 RotorToSensorRatio = units::dimensionless::scalar_t{RotorToSensorRatioVal};
2704 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_FeedbackRemoteSensorID, string_c_str, string_length, &FeedbackRemoteSensorID);
2705 double VelocityFilterTimeConstantVal = VelocityFilterTimeConstant.to<double>();
2706 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VelocityFilterTimeConstant, string_c_str, string_length, &VelocityFilterTimeConstantVal);
2707 VelocityFilterTimeConstant = units::time::second_t{VelocityFilterTimeConstantVal};
2708 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
2709 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
2710 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
2711 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ExternalFeedbackSensorSource, string_c_str, string_length, &ExternalFeedbackSensorSource.value);
2712 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_SensorPhase, string_c_str, string_length, &SensorPhase.value);
2713 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, string_c_str, string_length, &QuadratureEdgesPerRotation);
2714 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
2715 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
2716 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
2717 return 0;
2718 }
2719};
2720
2721
2722/**
2723 * \brief Configs related to sensors used for differential control of
2724 * a mechanism.
2725 *
2726 * \details Includes the differential sensor sources and IDs.
2727 */
2729{
2730public:
2731 constexpr DifferentialSensorsConfigs() = default;
2732
2733 /**
2734 * \brief Choose what sensor source is used for differential control
2735 * of a mechanism. The default is Disabled. All other options
2736 * require setting the DifferentialTalonFXSensorID, as the average of
2737 * this Talon FX's sensor and the remote TalonFX's sensor is used for
2738 * the differential controller's primary targets.
2739 *
2740 * Choose RemoteTalonFX_Diff to use another TalonFX on the same CAN
2741 * bus. Talon FX will update its differential position and velocity
2742 * whenever the remote TalonFX publishes its information on CAN bus.
2743 * The differential controller will use the difference between this
2744 * TalonFX's sensor and the remote Talon FX's sensor for the
2745 * differential component of the output.
2746 *
2747 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2748 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2749 * also requires setting DifferentialRemoteSensorID). Talon FX will
2750 * update its differential position to match the selected value
2751 * whenever Pigeon2 publishes its information on CAN bus. Note that
2752 * the Talon FX differential position will be in rotations and not
2753 * degrees.
2754 *
2755 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
2756 * (this also requires setting DifferentialRemoteSensorID). Talon FX
2757 * will update its differential position and velocity to match the
2758 * CANcoder whenever CANcoder publishes its information on CAN bus.
2759 *
2760 */
2762 /**
2763 * \brief Device ID of which remote Talon FX to use. This is used
2764 * when the Differential Sensor Source is not disabled.
2765 *
2766 * - Minimum Value: 0
2767 * - Maximum Value: 62
2768 * - Default Value: 0
2769 * - Units:
2770 */
2772 /**
2773 * \brief Device ID of which remote sensor to use on the differential
2774 * axis. This is used when the Differential Sensor Source is not
2775 * RemoteTalonFX_Diff.
2776 *
2777 * - Minimum Value: 0
2778 * - Maximum Value: 62
2779 * - Default Value: 0
2780 * - Units:
2781 */
2783
2784 /**
2785 * \brief Modifies this configuration's DifferentialSensorSource parameter and returns itself for
2786 * method-chaining and easier to use config API.
2787 *
2788 * Choose what sensor source is used for differential control of a
2789 * mechanism. The default is Disabled. All other options require
2790 * setting the DifferentialTalonFXSensorID, as the average of this
2791 * Talon FX's sensor and the remote TalonFX's sensor is used for the
2792 * differential controller's primary targets.
2793 *
2794 * Choose RemoteTalonFX_Diff to use another TalonFX on the same CAN
2795 * bus. Talon FX will update its differential position and velocity
2796 * whenever the remote TalonFX publishes its information on CAN bus.
2797 * The differential controller will use the difference between this
2798 * TalonFX's sensor and the remote Talon FX's sensor for the
2799 * differential component of the output.
2800 *
2801 * Choose RemotePigeon2_Yaw, RemotePigeon2_Pitch, and
2802 * RemotePigeon2_Roll to use another Pigeon2 on the same CAN bus (this
2803 * also requires setting DifferentialRemoteSensorID). Talon FX will
2804 * update its differential position to match the selected value
2805 * whenever Pigeon2 publishes its information on CAN bus. Note that
2806 * the Talon FX differential position will be in rotations and not
2807 * degrees.
2808 *
2809 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
2810 * (this also requires setting DifferentialRemoteSensorID). Talon FX
2811 * will update its differential position and velocity to match the
2812 * CANcoder whenever CANcoder publishes its information on CAN bus.
2813 *
2814 *
2815 * \param newDifferentialSensorSource Parameter to modify
2816 * \returns Itself
2817 */
2819 {
2820 DifferentialSensorSource = std::move(newDifferentialSensorSource);
2821 return *this;
2822 }
2823
2824 /**
2825 * \brief Modifies this configuration's DifferentialTalonFXSensorID parameter and returns itself for
2826 * method-chaining and easier to use config API.
2827 *
2828 * Device ID of which remote Talon FX to use. This is used when the
2829 * Differential Sensor Source is not disabled.
2830 *
2831 * - Minimum Value: 0
2832 * - Maximum Value: 62
2833 * - Default Value: 0
2834 * - Units:
2835 *
2836 * \param newDifferentialTalonFXSensorID Parameter to modify
2837 * \returns Itself
2838 */
2839 constexpr DifferentialSensorsConfigs &WithDifferentialTalonFXSensorID(int newDifferentialTalonFXSensorID)
2840 {
2841 DifferentialTalonFXSensorID = std::move(newDifferentialTalonFXSensorID);
2842 return *this;
2843 }
2844
2845 /**
2846 * \brief Modifies this configuration's DifferentialRemoteSensorID parameter and returns itself for
2847 * method-chaining and easier to use config API.
2848 *
2849 * Device ID of which remote sensor to use on the differential axis.
2850 * This is used when the Differential Sensor Source is not
2851 * RemoteTalonFX_Diff.
2852 *
2853 * - Minimum Value: 0
2854 * - Maximum Value: 62
2855 * - Default Value: 0
2856 * - Units:
2857 *
2858 * \param newDifferentialRemoteSensorID Parameter to modify
2859 * \returns Itself
2860 */
2861 constexpr DifferentialSensorsConfigs &WithDifferentialRemoteSensorID(int newDifferentialRemoteSensorID)
2862 {
2863 DifferentialRemoteSensorID = std::move(newDifferentialRemoteSensorID);
2864 return *this;
2865 }
2866
2867
2868
2869 std::string ToString() const override
2870 {
2871 std::stringstream ss;
2872 ss << "Config Group: DifferentialSensors" << std::endl;
2873 ss << " DifferentialSensorSource: " << DifferentialSensorSource << std::endl;
2874 ss << " DifferentialTalonFXSensorID: " << DifferentialTalonFXSensorID << std::endl;
2875 ss << " DifferentialRemoteSensorID: " << DifferentialRemoteSensorID << std::endl;
2876 return ss.str();
2877 }
2878
2879 std::string Serialize() const override
2880 {
2881 std::stringstream ss;
2882 char *ref;
2883 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialSensorSource, DifferentialSensorSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2884 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialTalonFXSensorID, DifferentialTalonFXSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2885 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialRemoteSensorID, DifferentialRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
2886 return ss.str();
2887 }
2888
2889 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
2890 {
2891 const char *string_c_str = to_deserialize.c_str();
2892 size_t string_length = to_deserialize.length();
2893 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialSensorSource, string_c_str, string_length, &DifferentialSensorSource.value);
2894 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialTalonFXSensorID, string_c_str, string_length, &DifferentialTalonFXSensorID);
2895 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_DifferentialRemoteSensorID, string_c_str, string_length, &DifferentialRemoteSensorID);
2896 return 0;
2897 }
2898};
2899
2900
2901/**
2902 * \brief Configs related to constants used for differential control
2903 * of a mechanism.
2904 *
2905 * \details Includes the differential peak outputs.
2906 */
2908{
2909public:
2910 constexpr DifferentialConstantsConfigs() = default;
2911
2912 /**
2913 * \brief Maximum differential output during duty cycle based
2914 * differential control modes.
2915 *
2916 * - Minimum Value: 0.0
2917 * - Maximum Value: 2.0
2918 * - Default Value: 2
2919 * - Units: fractional
2920 */
2921 units::dimensionless::scalar_t PeakDifferentialDutyCycle = 2;
2922 /**
2923 * \brief Maximum differential output during voltage based
2924 * differential control modes.
2925 *
2926 * - Minimum Value: 0.0
2927 * - Maximum Value: 32
2928 * - Default Value: 32
2929 * - Units: V
2930 */
2931 units::voltage::volt_t PeakDifferentialVoltage = 32_V;
2932 /**
2933 * \brief Maximum differential output during torque current based
2934 * differential control modes.
2935 *
2936 * - Minimum Value: 0.0
2937 * - Maximum Value: 1600
2938 * - Default Value: 1600
2939 * - Units: A
2940 */
2941 units::current::ampere_t PeakDifferentialTorqueCurrent = 1600_A;
2942
2943 /**
2944 * \brief Modifies this configuration's PeakDifferentialDutyCycle parameter and returns itself for
2945 * method-chaining and easier to use config API.
2946 *
2947 * Maximum differential output during duty cycle based differential
2948 * control modes.
2949 *
2950 * - Minimum Value: 0.0
2951 * - Maximum Value: 2.0
2952 * - Default Value: 2
2953 * - Units: fractional
2954 *
2955 * \param newPeakDifferentialDutyCycle Parameter to modify
2956 * \returns Itself
2957 */
2958 constexpr DifferentialConstantsConfigs &WithPeakDifferentialDutyCycle(units::dimensionless::scalar_t newPeakDifferentialDutyCycle)
2959 {
2960 PeakDifferentialDutyCycle = std::move(newPeakDifferentialDutyCycle);
2961 return *this;
2962 }
2963
2964 /**
2965 * \brief Modifies this configuration's PeakDifferentialVoltage parameter and returns itself for
2966 * method-chaining and easier to use config API.
2967 *
2968 * Maximum differential output during voltage based differential
2969 * control modes.
2970 *
2971 * - Minimum Value: 0.0
2972 * - Maximum Value: 32
2973 * - Default Value: 32
2974 * - Units: V
2975 *
2976 * \param newPeakDifferentialVoltage Parameter to modify
2977 * \returns Itself
2978 */
2979 constexpr DifferentialConstantsConfigs &WithPeakDifferentialVoltage(units::voltage::volt_t newPeakDifferentialVoltage)
2980 {
2981 PeakDifferentialVoltage = std::move(newPeakDifferentialVoltage);
2982 return *this;
2983 }
2984
2985 /**
2986 * \brief Modifies this configuration's PeakDifferentialTorqueCurrent parameter and returns itself for
2987 * method-chaining and easier to use config API.
2988 *
2989 * Maximum differential output during torque current based
2990 * differential control modes.
2991 *
2992 * - Minimum Value: 0.0
2993 * - Maximum Value: 1600
2994 * - Default Value: 1600
2995 * - Units: A
2996 *
2997 * \param newPeakDifferentialTorqueCurrent Parameter to modify
2998 * \returns Itself
2999 */
3000 constexpr DifferentialConstantsConfigs &WithPeakDifferentialTorqueCurrent(units::current::ampere_t newPeakDifferentialTorqueCurrent)
3001 {
3002 PeakDifferentialTorqueCurrent = std::move(newPeakDifferentialTorqueCurrent);
3003 return *this;
3004 }
3005
3006
3007
3008 std::string ToString() const override
3009 {
3010 std::stringstream ss;
3011 ss << "Config Group: DifferentialConstants" << std::endl;
3012 ss << " PeakDifferentialDutyCycle: " << PeakDifferentialDutyCycle.to<double>() << " fractional" << std::endl;
3013 ss << " PeakDifferentialVoltage: " << PeakDifferentialVoltage.to<double>() << " V" << std::endl;
3014 ss << " PeakDifferentialTorqueCurrent: " << PeakDifferentialTorqueCurrent.to<double>() << " A" << std::endl;
3015 return ss.str();
3016 }
3017
3018 std::string Serialize() const override
3019 {
3020 std::stringstream ss;
3021 char *ref;
3022 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffDC, PeakDifferentialDutyCycle.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3023 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffV, PeakDifferentialVoltage.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3024 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffTorqCurr, PeakDifferentialTorqueCurrent.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3025 return ss.str();
3026 }
3027
3028 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3029 {
3030 const char *string_c_str = to_deserialize.c_str();
3031 size_t string_length = to_deserialize.length();
3032 double PeakDifferentialDutyCycleVal = PeakDifferentialDutyCycle.to<double>();
3033 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffDC, string_c_str, string_length, &PeakDifferentialDutyCycleVal);
3034 PeakDifferentialDutyCycle = units::dimensionless::scalar_t{PeakDifferentialDutyCycleVal};
3035 double PeakDifferentialVoltageVal = PeakDifferentialVoltage.to<double>();
3036 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffV, string_c_str, string_length, &PeakDifferentialVoltageVal);
3037 PeakDifferentialVoltage = units::voltage::volt_t{PeakDifferentialVoltageVal};
3038 double PeakDifferentialTorqueCurrentVal = PeakDifferentialTorqueCurrent.to<double>();
3039 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PeakDiffTorqCurr, string_c_str, string_length, &PeakDifferentialTorqueCurrentVal);
3040 PeakDifferentialTorqueCurrent = units::current::ampere_t{PeakDifferentialTorqueCurrentVal};
3041 return 0;
3042 }
3043};
3044
3045
3046/**
3047 * \brief Configs that affect the open-loop control of this motor
3048 * controller.
3049 *
3050 * \details Open-loop ramp rates for the various control types.
3051 */
3053{
3054public:
3055 constexpr OpenLoopRampsConfigs() = default;
3056
3057 /**
3058 * \brief If non-zero, this determines how much time to ramp from 0%
3059 * output to 100% during the open-loop DutyCycleOut control mode.
3060 *
3061 * This provides an easy way to limit the acceleration of the motor.
3062 * However, the acceleration and current draw of the motor can be
3063 * better restricted using current limits instead of a ramp rate.
3064 *
3065 * - Minimum Value: 0
3066 * - Maximum Value: 1
3067 * - Default Value: 0
3068 * - Units: seconds
3069 */
3070 units::time::second_t DutyCycleOpenLoopRampPeriod = 0_s;
3071 /**
3072 * \brief If non-zero, this determines how much time to ramp from 0V
3073 * output to 12V during the open-loop VoltageOut control mode.
3074 *
3075 * This provides an easy way to limit the acceleration of the motor.
3076 * However, the acceleration and current draw of the motor can be
3077 * better restricted using current limits instead of a ramp rate.
3078 *
3079 * - Minimum Value: 0
3080 * - Maximum Value: 1
3081 * - Default Value: 0
3082 * - Units: seconds
3083 */
3084 units::time::second_t VoltageOpenLoopRampPeriod = 0_s;
3085 /**
3086 * \brief If non-zero, this determines how much time to ramp from 0A
3087 * output to 300A during the open-loop TorqueCurrent control mode.
3088 *
3089 * Since TorqueCurrent is directly proportional to acceleration, this
3090 * ramp limits jerk instead of acceleration.
3091 *
3092 * - Minimum Value: 0
3093 * - Maximum Value: 10
3094 * - Default Value: 0
3095 * - Units: seconds
3096 */
3097 units::time::second_t TorqueOpenLoopRampPeriod = 0_s;
3098
3099 /**
3100 * \brief Modifies this configuration's DutyCycleOpenLoopRampPeriod parameter and returns itself for
3101 * method-chaining and easier to use config API.
3102 *
3103 * If non-zero, this determines how much time to ramp from 0% output
3104 * to 100% during the open-loop DutyCycleOut control mode.
3105 *
3106 * This provides an easy way to limit the acceleration of the motor.
3107 * However, the acceleration and current draw of the motor can be
3108 * better restricted using current limits instead of a ramp rate.
3109 *
3110 * - Minimum Value: 0
3111 * - Maximum Value: 1
3112 * - Default Value: 0
3113 * - Units: seconds
3114 *
3115 * \param newDutyCycleOpenLoopRampPeriod Parameter to modify
3116 * \returns Itself
3117 */
3118 constexpr OpenLoopRampsConfigs &WithDutyCycleOpenLoopRampPeriod(units::time::second_t newDutyCycleOpenLoopRampPeriod)
3119 {
3120 DutyCycleOpenLoopRampPeriod = std::move(newDutyCycleOpenLoopRampPeriod);
3121 return *this;
3122 }
3123
3124 /**
3125 * \brief Modifies this configuration's VoltageOpenLoopRampPeriod parameter and returns itself for
3126 * method-chaining and easier to use config API.
3127 *
3128 * If non-zero, this determines how much time to ramp from 0V output
3129 * to 12V during the open-loop VoltageOut control mode.
3130 *
3131 * This provides an easy way to limit the acceleration of the motor.
3132 * However, the acceleration and current draw of the motor can be
3133 * better restricted using current limits instead of a ramp rate.
3134 *
3135 * - Minimum Value: 0
3136 * - Maximum Value: 1
3137 * - Default Value: 0
3138 * - Units: seconds
3139 *
3140 * \param newVoltageOpenLoopRampPeriod Parameter to modify
3141 * \returns Itself
3142 */
3143 constexpr OpenLoopRampsConfigs &WithVoltageOpenLoopRampPeriod(units::time::second_t newVoltageOpenLoopRampPeriod)
3144 {
3145 VoltageOpenLoopRampPeriod = std::move(newVoltageOpenLoopRampPeriod);
3146 return *this;
3147 }
3148
3149 /**
3150 * \brief Modifies this configuration's TorqueOpenLoopRampPeriod parameter and returns itself for
3151 * method-chaining and easier to use config API.
3152 *
3153 * If non-zero, this determines how much time to ramp from 0A output
3154 * to 300A during the open-loop TorqueCurrent control mode.
3155 *
3156 * Since TorqueCurrent is directly proportional to acceleration, this
3157 * ramp limits jerk instead of acceleration.
3158 *
3159 * - Minimum Value: 0
3160 * - Maximum Value: 10
3161 * - Default Value: 0
3162 * - Units: seconds
3163 *
3164 * \param newTorqueOpenLoopRampPeriod Parameter to modify
3165 * \returns Itself
3166 */
3167 constexpr OpenLoopRampsConfigs &WithTorqueOpenLoopRampPeriod(units::time::second_t newTorqueOpenLoopRampPeriod)
3168 {
3169 TorqueOpenLoopRampPeriod = std::move(newTorqueOpenLoopRampPeriod);
3170 return *this;
3171 }
3172
3173
3174
3175 std::string ToString() const override
3176 {
3177 std::stringstream ss;
3178 ss << "Config Group: OpenLoopRamps" << std::endl;
3179 ss << " DutyCycleOpenLoopRampPeriod: " << DutyCycleOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3180 ss << " VoltageOpenLoopRampPeriod: " << VoltageOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3181 ss << " TorqueOpenLoopRampPeriod: " << TorqueOpenLoopRampPeriod.to<double>() << " seconds" << std::endl;
3182 return ss.str();
3183 }
3184
3185 std::string Serialize() const override
3186 {
3187 std::stringstream ss;
3188 char *ref;
3189 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleOpenLoopRampPeriod, DutyCycleOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3190 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageOpenLoopRampPeriod, VoltageOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3191 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueOpenLoopRampPeriod, TorqueOpenLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3192 return ss.str();
3193 }
3194
3195 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3196 {
3197 const char *string_c_str = to_deserialize.c_str();
3198 size_t string_length = to_deserialize.length();
3199 double DutyCycleOpenLoopRampPeriodVal = DutyCycleOpenLoopRampPeriod.to<double>();
3200 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleOpenLoopRampPeriod, string_c_str, string_length, &DutyCycleOpenLoopRampPeriodVal);
3201 DutyCycleOpenLoopRampPeriod = units::time::second_t{DutyCycleOpenLoopRampPeriodVal};
3202 double VoltageOpenLoopRampPeriodVal = VoltageOpenLoopRampPeriod.to<double>();
3203 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageOpenLoopRampPeriod, string_c_str, string_length, &VoltageOpenLoopRampPeriodVal);
3204 VoltageOpenLoopRampPeriod = units::time::second_t{VoltageOpenLoopRampPeriodVal};
3205 double TorqueOpenLoopRampPeriodVal = TorqueOpenLoopRampPeriod.to<double>();
3206 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueOpenLoopRampPeriod, string_c_str, string_length, &TorqueOpenLoopRampPeriodVal);
3207 TorqueOpenLoopRampPeriod = units::time::second_t{TorqueOpenLoopRampPeriodVal};
3208 return 0;
3209 }
3210};
3211
3212
3213/**
3214 * \brief Configs that affect the closed-loop control of this motor
3215 * controller.
3216 *
3217 * \details Closed-loop ramp rates for the various control types.
3218 */
3220{
3221public:
3222 constexpr ClosedLoopRampsConfigs() = default;
3223
3224 /**
3225 * \brief If non-zero, this determines how much time to ramp from 0%
3226 * output to 100% during the closed-loop DutyCycle control modes.
3227 *
3228 * If the goal is to limit acceleration, it is more useful to ramp the
3229 * closed-loop setpoint instead of the output. This can be achieved
3230 * using Motion Magic® controls.
3231 *
3232 * The acceleration and current draw of the motor can also be better
3233 * restricted using current limits instead of a ramp rate.
3234 *
3235 * - Minimum Value: 0
3236 * - Maximum Value: 1
3237 * - Default Value: 0
3238 * - Units: seconds
3239 */
3240 units::time::second_t DutyCycleClosedLoopRampPeriod = 0_s;
3241 /**
3242 * \brief If non-zero, this determines how much time to ramp from 0V
3243 * output to 12V during the closed-loop Voltage control modes.
3244 *
3245 * If the goal is to limit acceleration, it is more useful to ramp the
3246 * closed-loop setpoint instead of the output. This can be achieved
3247 * using Motion Magic® controls.
3248 *
3249 * The acceleration and current draw of the motor can also be better
3250 * restricted using current limits instead of a ramp rate.
3251 *
3252 * - Minimum Value: 0
3253 * - Maximum Value: 1
3254 * - Default Value: 0
3255 * - Units: seconds
3256 */
3257 units::time::second_t VoltageClosedLoopRampPeriod = 0_s;
3258 /**
3259 * \brief If non-zero, this determines how much time to ramp from 0A
3260 * output to 300A during the closed-loop TorqueCurrent control modes.
3261 *
3262 * Since TorqueCurrent is directly proportional to acceleration, this
3263 * ramp limits jerk instead of acceleration.
3264 *
3265 * If the goal is to limit acceleration or jerk, it is more useful to
3266 * ramp the closed-loop setpoint instead of the output. This can be
3267 * achieved using Motion Magic® controls.
3268 *
3269 * The acceleration and current draw of the motor can also be better
3270 * restricted using current limits instead of a ramp rate.
3271 *
3272 * - Minimum Value: 0
3273 * - Maximum Value: 10
3274 * - Default Value: 0
3275 * - Units: seconds
3276 */
3277 units::time::second_t TorqueClosedLoopRampPeriod = 0_s;
3278
3279 /**
3280 * \brief Modifies this configuration's DutyCycleClosedLoopRampPeriod parameter and returns itself for
3281 * method-chaining and easier to use config API.
3282 *
3283 * If non-zero, this determines how much time to ramp from 0% output
3284 * to 100% during the closed-loop DutyCycle control modes.
3285 *
3286 * If the goal is to limit acceleration, it is more useful to ramp the
3287 * closed-loop setpoint instead of the output. This can be achieved
3288 * using Motion Magic® controls.
3289 *
3290 * The acceleration and current draw of the motor can also be better
3291 * restricted using current limits instead of a ramp rate.
3292 *
3293 * - Minimum Value: 0
3294 * - Maximum Value: 1
3295 * - Default Value: 0
3296 * - Units: seconds
3297 *
3298 * \param newDutyCycleClosedLoopRampPeriod Parameter to modify
3299 * \returns Itself
3300 */
3301 constexpr ClosedLoopRampsConfigs &WithDutyCycleClosedLoopRampPeriod(units::time::second_t newDutyCycleClosedLoopRampPeriod)
3302 {
3303 DutyCycleClosedLoopRampPeriod = std::move(newDutyCycleClosedLoopRampPeriod);
3304 return *this;
3305 }
3306
3307 /**
3308 * \brief Modifies this configuration's VoltageClosedLoopRampPeriod parameter and returns itself for
3309 * method-chaining and easier to use config API.
3310 *
3311 * If non-zero, this determines how much time to ramp from 0V output
3312 * to 12V during the closed-loop Voltage control modes.
3313 *
3314 * If the goal is to limit acceleration, it is more useful to ramp the
3315 * closed-loop setpoint instead of the output. This can be achieved
3316 * using Motion Magic® controls.
3317 *
3318 * The acceleration and current draw of the motor can also be better
3319 * restricted using current limits instead of a ramp rate.
3320 *
3321 * - Minimum Value: 0
3322 * - Maximum Value: 1
3323 * - Default Value: 0
3324 * - Units: seconds
3325 *
3326 * \param newVoltageClosedLoopRampPeriod Parameter to modify
3327 * \returns Itself
3328 */
3329 constexpr ClosedLoopRampsConfigs &WithVoltageClosedLoopRampPeriod(units::time::second_t newVoltageClosedLoopRampPeriod)
3330 {
3331 VoltageClosedLoopRampPeriod = std::move(newVoltageClosedLoopRampPeriod);
3332 return *this;
3333 }
3334
3335 /**
3336 * \brief Modifies this configuration's TorqueClosedLoopRampPeriod parameter and returns itself for
3337 * method-chaining and easier to use config API.
3338 *
3339 * If non-zero, this determines how much time to ramp from 0A output
3340 * to 300A during the closed-loop TorqueCurrent control modes.
3341 *
3342 * Since TorqueCurrent is directly proportional to acceleration, this
3343 * ramp limits jerk instead of acceleration.
3344 *
3345 * If the goal is to limit acceleration or jerk, it is more useful to
3346 * ramp the closed-loop setpoint instead of the output. This can be
3347 * achieved using Motion Magic® controls.
3348 *
3349 * The acceleration and current draw of the motor can also be better
3350 * restricted using current limits instead of a ramp rate.
3351 *
3352 * - Minimum Value: 0
3353 * - Maximum Value: 10
3354 * - Default Value: 0
3355 * - Units: seconds
3356 *
3357 * \param newTorqueClosedLoopRampPeriod Parameter to modify
3358 * \returns Itself
3359 */
3360 constexpr ClosedLoopRampsConfigs &WithTorqueClosedLoopRampPeriod(units::time::second_t newTorqueClosedLoopRampPeriod)
3361 {
3362 TorqueClosedLoopRampPeriod = std::move(newTorqueClosedLoopRampPeriod);
3363 return *this;
3364 }
3365
3366
3367
3368 std::string ToString() const override
3369 {
3370 std::stringstream ss;
3371 ss << "Config Group: ClosedLoopRamps" << std::endl;
3372 ss << " DutyCycleClosedLoopRampPeriod: " << DutyCycleClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3373 ss << " VoltageClosedLoopRampPeriod: " << VoltageClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3374 ss << " TorqueClosedLoopRampPeriod: " << TorqueClosedLoopRampPeriod.to<double>() << " seconds" << std::endl;
3375 return ss.str();
3376 }
3377
3378 std::string Serialize() const override
3379 {
3380 std::stringstream ss;
3381 char *ref;
3382 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleClosedLoopRampPeriod, DutyCycleClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3383 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageClosedLoopRampPeriod, VoltageClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3384 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueClosedLoopRampPeriod, TorqueClosedLoopRampPeriod.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3385 return ss.str();
3386 }
3387
3388 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3389 {
3390 const char *string_c_str = to_deserialize.c_str();
3391 size_t string_length = to_deserialize.length();
3392 double DutyCycleClosedLoopRampPeriodVal = DutyCycleClosedLoopRampPeriod.to<double>();
3393 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_DutyCycleClosedLoopRampPeriod, string_c_str, string_length, &DutyCycleClosedLoopRampPeriodVal);
3394 DutyCycleClosedLoopRampPeriod = units::time::second_t{DutyCycleClosedLoopRampPeriodVal};
3395 double VoltageClosedLoopRampPeriodVal = VoltageClosedLoopRampPeriod.to<double>();
3396 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_VoltageClosedLoopRampPeriod, string_c_str, string_length, &VoltageClosedLoopRampPeriodVal);
3397 VoltageClosedLoopRampPeriod = units::time::second_t{VoltageClosedLoopRampPeriodVal};
3398 double TorqueClosedLoopRampPeriodVal = TorqueClosedLoopRampPeriod.to<double>();
3399 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_TorqueClosedLoopRampPeriod, string_c_str, string_length, &TorqueClosedLoopRampPeriodVal);
3400 TorqueClosedLoopRampPeriod = units::time::second_t{TorqueClosedLoopRampPeriodVal};
3401 return 0;
3402 }
3403};
3404
3405
3406/**
3407 * \brief Configs that change how the motor controller behaves under
3408 * different limit switch states.
3409 *
3410 * \details Includes configs such as enabling limit switches,
3411 * configuring the remote sensor ID, the source, and the
3412 * position to set on limit.
3413 */
3415{
3416public:
3417 constexpr HardwareLimitSwitchConfigs() = default;
3418
3419 /**
3420 * \brief Determines if the forward limit switch is normally-open
3421 * (default) or normally-closed.
3422 *
3423 */
3425 /**
3426 * \brief If enabled, the position is automatically set to a specific
3427 * value, specified by ForwardLimitAutosetPositionValue, when the
3428 * forward limit switch is asserted.
3429 *
3430 * - Default Value: False
3431 */
3433 /**
3434 * \brief The value to automatically set the position to when the
3435 * forward limit switch is asserted. This has no effect if
3436 * ForwardLimitAutosetPositionEnable is false.
3437 *
3438 * - Minimum Value: -3.4e+38
3439 * - Maximum Value: 3.4e+38
3440 * - Default Value: 0
3441 * - Units: rotations
3442 */
3443 units::angle::turn_t ForwardLimitAutosetPositionValue = 0_tr;
3444 /**
3445 * \brief If enabled, motor output is set to neutral when the forward
3446 * limit switch is asserted and positive output is requested.
3447 *
3448 * - Default Value: True
3449 */
3451 /**
3452 * \brief Determines where to poll the forward limit switch. This
3453 * defaults to the forward limit switch pin on the limit switch
3454 * connector.
3455 *
3456 * Choose RemoteTalonFX to use the forward limit switch attached to
3457 * another Talon FX on the same CAN bus (this also requires setting
3458 * ForwardLimitRemoteSensorID).
3459 *
3460 * Choose RemoteCANifier to use the forward limit switch attached to
3461 * another CANifier on the same CAN bus (this also requires setting
3462 * ForwardLimitRemoteSensorID).
3463 *
3464 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3465 * (this also requires setting ForwardLimitRemoteSensorID). The
3466 * forward limit will assert when the CANcoder magnet strength changes
3467 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3468 *
3469 */
3471 /**
3472 * \brief Device ID of the remote device if using remote limit switch
3473 * features for the forward limit switch.
3474 *
3475 * - Minimum Value: 0
3476 * - Maximum Value: 62
3477 * - Default Value: 0
3478 * - Units:
3479 */
3481 /**
3482 * \brief Determines if the reverse limit switch is normally-open
3483 * (default) or normally-closed.
3484 *
3485 */
3487 /**
3488 * \brief If enabled, the position is automatically set to a specific
3489 * value, specified by ReverseLimitAutosetPositionValue, when the
3490 * reverse limit switch is asserted.
3491 *
3492 * - Default Value: False
3493 */
3495 /**
3496 * \brief The value to automatically set the position to when the
3497 * reverse limit switch is asserted. This has no effect if
3498 * ReverseLimitAutosetPositionEnable is false.
3499 *
3500 * - Minimum Value: -3.4e+38
3501 * - Maximum Value: 3.4e+38
3502 * - Default Value: 0
3503 * - Units: rotations
3504 */
3505 units::angle::turn_t ReverseLimitAutosetPositionValue = 0_tr;
3506 /**
3507 * \brief If enabled, motor output is set to neutral when reverse
3508 * limit switch is asseted and negative output is requested.
3509 *
3510 * - Default Value: True
3511 */
3513 /**
3514 * \brief Determines where to poll the reverse limit switch. This
3515 * defaults to the reverse limit switch pin on the limit switch
3516 * connector.
3517 *
3518 * Choose RemoteTalonFX to use the reverse limit switch attached to
3519 * another Talon FX on the same CAN bus (this also requires setting
3520 * ReverseLimitRemoteSensorID).
3521 *
3522 * Choose RemoteCANifier to use the reverse limit switch attached to
3523 * another CANifier on the same CAN bus (this also requires setting
3524 * ReverseLimitRemoteSensorID).
3525 *
3526 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3527 * (this also requires setting ReverseLimitRemoteSensorID). The
3528 * reverse limit will assert when the CANcoder magnet strength changes
3529 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3530 *
3531 */
3533 /**
3534 * \brief Device ID of the remote device if using remote limit switch
3535 * features for the reverse limit switch.
3536 *
3537 * - Minimum Value: 0
3538 * - Maximum Value: 62
3539 * - Default Value: 0
3540 * - Units:
3541 */
3543
3544 /**
3545 * \brief Modifies this configuration's ForwardLimitType parameter and returns itself for
3546 * method-chaining and easier to use config API.
3547 *
3548 * Determines if the forward limit switch is normally-open (default)
3549 * or normally-closed.
3550 *
3551 *
3552 * \param newForwardLimitType Parameter to modify
3553 * \returns Itself
3554 */
3556 {
3557 ForwardLimitType = std::move(newForwardLimitType);
3558 return *this;
3559 }
3560
3561 /**
3562 * \brief Modifies this configuration's ForwardLimitAutosetPositionEnable parameter and returns itself for
3563 * method-chaining and easier to use config API.
3564 *
3565 * If enabled, the position is automatically set to a specific value,
3566 * specified by ForwardLimitAutosetPositionValue, when the forward
3567 * limit switch is asserted.
3568 *
3569 * - Default Value: False
3570 *
3571 * \param newForwardLimitAutosetPositionEnable Parameter to modify
3572 * \returns Itself
3573 */
3574 constexpr HardwareLimitSwitchConfigs &WithForwardLimitAutosetPositionEnable(bool newForwardLimitAutosetPositionEnable)
3575 {
3576 ForwardLimitAutosetPositionEnable = std::move(newForwardLimitAutosetPositionEnable);
3577 return *this;
3578 }
3579
3580 /**
3581 * \brief Modifies this configuration's ForwardLimitAutosetPositionValue parameter and returns itself for
3582 * method-chaining and easier to use config API.
3583 *
3584 * The value to automatically set the position to when the forward
3585 * limit switch is asserted. This has no effect if
3586 * ForwardLimitAutosetPositionEnable is false.
3587 *
3588 * - Minimum Value: -3.4e+38
3589 * - Maximum Value: 3.4e+38
3590 * - Default Value: 0
3591 * - Units: rotations
3592 *
3593 * \param newForwardLimitAutosetPositionValue Parameter to modify
3594 * \returns Itself
3595 */
3596 constexpr HardwareLimitSwitchConfigs &WithForwardLimitAutosetPositionValue(units::angle::turn_t newForwardLimitAutosetPositionValue)
3597 {
3598 ForwardLimitAutosetPositionValue = std::move(newForwardLimitAutosetPositionValue);
3599 return *this;
3600 }
3601
3602 /**
3603 * \brief Modifies this configuration's ForwardLimitEnable parameter and returns itself for
3604 * method-chaining and easier to use config API.
3605 *
3606 * If enabled, motor output is set to neutral when the forward limit
3607 * switch is asserted and positive output is requested.
3608 *
3609 * - Default Value: True
3610 *
3611 * \param newForwardLimitEnable Parameter to modify
3612 * \returns Itself
3613 */
3614 constexpr HardwareLimitSwitchConfigs &WithForwardLimitEnable(bool newForwardLimitEnable)
3615 {
3616 ForwardLimitEnable = std::move(newForwardLimitEnable);
3617 return *this;
3618 }
3619
3620 /**
3621 * \brief Modifies this configuration's ForwardLimitSource parameter and returns itself for
3622 * method-chaining and easier to use config API.
3623 *
3624 * Determines where to poll the forward limit switch. This defaults
3625 * to the forward limit switch pin on the limit switch connector.
3626 *
3627 * Choose RemoteTalonFX to use the forward limit switch attached to
3628 * another Talon FX on the same CAN bus (this also requires setting
3629 * ForwardLimitRemoteSensorID).
3630 *
3631 * Choose RemoteCANifier to use the forward limit switch attached to
3632 * another CANifier on the same CAN bus (this also requires setting
3633 * ForwardLimitRemoteSensorID).
3634 *
3635 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3636 * (this also requires setting ForwardLimitRemoteSensorID). The
3637 * forward limit will assert when the CANcoder magnet strength changes
3638 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3639 *
3640 *
3641 * \param newForwardLimitSource Parameter to modify
3642 * \returns Itself
3643 */
3645 {
3646 ForwardLimitSource = std::move(newForwardLimitSource);
3647 return *this;
3648 }
3649
3650 /**
3651 * \brief Modifies this configuration's ForwardLimitRemoteSensorID parameter and returns itself for
3652 * method-chaining and easier to use config API.
3653 *
3654 * Device ID of the remote device if using remote limit switch
3655 * features for the forward limit switch.
3656 *
3657 * - Minimum Value: 0
3658 * - Maximum Value: 62
3659 * - Default Value: 0
3660 * - Units:
3661 *
3662 * \param newForwardLimitRemoteSensorID Parameter to modify
3663 * \returns Itself
3664 */
3665 constexpr HardwareLimitSwitchConfigs &WithForwardLimitRemoteSensorID(int newForwardLimitRemoteSensorID)
3666 {
3667 ForwardLimitRemoteSensorID = std::move(newForwardLimitRemoteSensorID);
3668 return *this;
3669 }
3670
3671 /**
3672 * \brief Modifies this configuration's ReverseLimitType parameter and returns itself for
3673 * method-chaining and easier to use config API.
3674 *
3675 * Determines if the reverse limit switch is normally-open (default)
3676 * or normally-closed.
3677 *
3678 *
3679 * \param newReverseLimitType Parameter to modify
3680 * \returns Itself
3681 */
3683 {
3684 ReverseLimitType = std::move(newReverseLimitType);
3685 return *this;
3686 }
3687
3688 /**
3689 * \brief Modifies this configuration's ReverseLimitAutosetPositionEnable parameter and returns itself for
3690 * method-chaining and easier to use config API.
3691 *
3692 * If enabled, the position is automatically set to a specific value,
3693 * specified by ReverseLimitAutosetPositionValue, when the reverse
3694 * limit switch is asserted.
3695 *
3696 * - Default Value: False
3697 *
3698 * \param newReverseLimitAutosetPositionEnable Parameter to modify
3699 * \returns Itself
3700 */
3701 constexpr HardwareLimitSwitchConfigs &WithReverseLimitAutosetPositionEnable(bool newReverseLimitAutosetPositionEnable)
3702 {
3703 ReverseLimitAutosetPositionEnable = std::move(newReverseLimitAutosetPositionEnable);
3704 return *this;
3705 }
3706
3707 /**
3708 * \brief Modifies this configuration's ReverseLimitAutosetPositionValue parameter and returns itself for
3709 * method-chaining and easier to use config API.
3710 *
3711 * The value to automatically set the position to when the reverse
3712 * limit switch is asserted. This has no effect if
3713 * ReverseLimitAutosetPositionEnable is false.
3714 *
3715 * - Minimum Value: -3.4e+38
3716 * - Maximum Value: 3.4e+38
3717 * - Default Value: 0
3718 * - Units: rotations
3719 *
3720 * \param newReverseLimitAutosetPositionValue Parameter to modify
3721 * \returns Itself
3722 */
3723 constexpr HardwareLimitSwitchConfigs &WithReverseLimitAutosetPositionValue(units::angle::turn_t newReverseLimitAutosetPositionValue)
3724 {
3725 ReverseLimitAutosetPositionValue = std::move(newReverseLimitAutosetPositionValue);
3726 return *this;
3727 }
3728
3729 /**
3730 * \brief Modifies this configuration's ReverseLimitEnable parameter and returns itself for
3731 * method-chaining and easier to use config API.
3732 *
3733 * If enabled, motor output is set to neutral when reverse limit
3734 * switch is asseted and negative output is requested.
3735 *
3736 * - Default Value: True
3737 *
3738 * \param newReverseLimitEnable Parameter to modify
3739 * \returns Itself
3740 */
3741 constexpr HardwareLimitSwitchConfigs &WithReverseLimitEnable(bool newReverseLimitEnable)
3742 {
3743 ReverseLimitEnable = std::move(newReverseLimitEnable);
3744 return *this;
3745 }
3746
3747 /**
3748 * \brief Modifies this configuration's ReverseLimitSource parameter and returns itself for
3749 * method-chaining and easier to use config API.
3750 *
3751 * Determines where to poll the reverse limit switch. This defaults
3752 * to the reverse limit switch pin on the limit switch connector.
3753 *
3754 * Choose RemoteTalonFX to use the reverse limit switch attached to
3755 * another Talon FX on the same CAN bus (this also requires setting
3756 * ReverseLimitRemoteSensorID).
3757 *
3758 * Choose RemoteCANifier to use the reverse limit switch attached to
3759 * another CANifier on the same CAN bus (this also requires setting
3760 * ReverseLimitRemoteSensorID).
3761 *
3762 * Choose RemoteCANcoder to use another CANcoder on the same CAN bus
3763 * (this also requires setting ReverseLimitRemoteSensorID). The
3764 * reverse limit will assert when the CANcoder magnet strength changes
3765 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3766 *
3767 *
3768 * \param newReverseLimitSource Parameter to modify
3769 * \returns Itself
3770 */
3772 {
3773 ReverseLimitSource = std::move(newReverseLimitSource);
3774 return *this;
3775 }
3776
3777 /**
3778 * \brief Modifies this configuration's ReverseLimitRemoteSensorID parameter and returns itself for
3779 * method-chaining and easier to use config API.
3780 *
3781 * Device ID of the remote device if using remote limit switch
3782 * features for the reverse limit switch.
3783 *
3784 * - Minimum Value: 0
3785 * - Maximum Value: 62
3786 * - Default Value: 0
3787 * - Units:
3788 *
3789 * \param newReverseLimitRemoteSensorID Parameter to modify
3790 * \returns Itself
3791 */
3792 constexpr HardwareLimitSwitchConfigs &WithReverseLimitRemoteSensorID(int newReverseLimitRemoteSensorID)
3793 {
3794 ReverseLimitRemoteSensorID = std::move(newReverseLimitRemoteSensorID);
3795 return *this;
3796 }
3797
3798 /**
3799 * \brief Helper method to configure this feedback group to use
3800 * RemoteTalonFX forward limit switch by passing in the TalonFX
3801 * object. When using RemoteTalonFX, the Talon FX will use the
3802 * forward limit switch attached to another Talon FX on the
3803 * same CAN bus.
3804 *
3805 * \param device TalonFX reference to use for RemoteTalonFX forward limit switch
3806 * \returns Itself
3807 */
3809
3810 /**
3811 * \brief Helper method to configure this feedback group to use
3812 * RemoteCANcoder forward limit switch by passing in the
3813 * CANcoder object. When using RemoteCANcoder, the Talon FX
3814 * will use another CANcoder on the same CAN bus. The forward
3815 * limit will assert when the CANcoder magnet strength changes
3816 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3817 *
3818 * \param device CANcoder reference to use for RemoteCANcoder forward limit switch
3819 * \returns Itself
3820 */
3822
3823 /**
3824 * \brief Helper method to configure this feedback group to use the
3825 * RemoteCANrange by passing in the CANrange object. The
3826 * forward limit will assert when the CANrange proximity detect
3827 * is tripped.
3828 *
3829 * \param device CANrange reference to use for RemoteCANrange forward limit switch
3830 * \returns Itself
3831 */
3833
3834 /**
3835 * \brief Helper method to configure this feedback group to use
3836 * RemoteCANdi forward limit switch on Signal 1 Input (S1IN) by
3837 * passing in the CANdi object. The forward limit will assert
3838 * when the CANdi Signal 1 Input (S1IN) pin matches the
3839 * configured closed state.
3840 *
3841 * \param device CANdi reference to use for RemoteCANdi forward limit switch
3842 * \returns Itself
3843 */
3845
3846 /**
3847 * \brief Helper method to configure this feedback group to use
3848 * RemoteCANdi forward limit switch on Signal 2 Input (S2IN) by
3849 * passing in the CANdi object. The forward limit will assert
3850 * when the CANdi Signal 2 Input (S2IN) pin matches the
3851 * configured closed state.
3852 *
3853 * \param device CANdi reference to use for RemoteCANdi forward limit switch
3854 * \returns Itself
3855 */
3857
3858 /**
3859 * \brief Helper method to configure this feedback group to use
3860 * RemoteTalonFX reverse limit switch by passing in the TalonFX
3861 * object. When using RemoteTalonFX, the Talon FX will use the
3862 * reverse limit switch attached to another Talon FX on the
3863 * same CAN bus.
3864 *
3865 * \param device TalonFX reference to use for RemoteTalonFX reverse limit switch
3866 * \returns Itself
3867 */
3869
3870 /**
3871 * \brief Helper method to configure this feedback group to use
3872 * RemoteCANcoder reverse limit switch by passing in the
3873 * CANcoder object. When using RemoteCANcoder, the Talon FX
3874 * will use another CANcoder on the same CAN bus. The reverse
3875 * limit will assert when the CANcoder magnet strength changes
3876 * from BAD (red) to ADEQUATE (orange) or GOOD (green).
3877 *
3878 * \param device CANcoder reference to use for RemoteCANcoder reverse limit switch
3879 * \returns Itself
3880 */
3882
3883 /**
3884 * \brief Helper method to configure this feedback group to use the
3885 * RemoteCANrange by passing in the CANrange object. The
3886 * reverse limit will assert when the CANrange proximity detect
3887 * is tripped.
3888 *
3889 * \param device CANrange reference to use for RemoteCANrange reverse limit switch
3890 * \returns Itself
3891 */
3893
3894 /**
3895 * \brief Helper method to configure this feedback group to use
3896 * RemoteCANdi reverse limit switch on Signal 1 Input (S1IN) by
3897 * passing in the CANdi object. The reverse limit will assert
3898 * when the CANdi Signal 1 Input (S1IN) pin matches the
3899 * configured closed state.
3900 *
3901 * \param device CANdi reference to use for RemoteCANdi reverse limit switch
3902 * \returns Itself
3903 */
3905
3906 /**
3907 * \brief Helper method to configure this feedback group to use
3908 * RemoteCANdi reverse limit switch on Signal 2 Input (S2IN) by
3909 * passing in the CANdi object. The reverse limit will assert
3910 * when the CANdi Signal 2 Input (S2IN) pin matches the
3911 * configured closed state.
3912 *
3913 * \param device CANdi reference to use for RemoteCANdi reverse limit switch
3914 * \returns Itself
3915 */
3917
3918
3919
3920 std::string ToString() const override
3921 {
3922 std::stringstream ss;
3923 ss << "Config Group: HardwareLimitSwitch" << std::endl;
3924 ss << " ForwardLimitType: " << ForwardLimitType << std::endl;
3925 ss << " ForwardLimitAutosetPositionEnable: " << ForwardLimitAutosetPositionEnable << std::endl;
3926 ss << " ForwardLimitAutosetPositionValue: " << ForwardLimitAutosetPositionValue.to<double>() << " rotations" << std::endl;
3927 ss << " ForwardLimitEnable: " << ForwardLimitEnable << std::endl;
3928 ss << " ForwardLimitSource: " << ForwardLimitSource << std::endl;
3929 ss << " ForwardLimitRemoteSensorID: " << ForwardLimitRemoteSensorID << std::endl;
3930 ss << " ReverseLimitType: " << ReverseLimitType << std::endl;
3931 ss << " ReverseLimitAutosetPositionEnable: " << ReverseLimitAutosetPositionEnable << std::endl;
3932 ss << " ReverseLimitAutosetPositionValue: " << ReverseLimitAutosetPositionValue.to<double>() << " rotations" << std::endl;
3933 ss << " ReverseLimitEnable: " << ReverseLimitEnable << std::endl;
3934 ss << " ReverseLimitSource: " << ReverseLimitSource << std::endl;
3935 ss << " ReverseLimitRemoteSensorID: " << ReverseLimitRemoteSensorID << std::endl;
3936 return ss.str();
3937 }
3938
3939 std::string Serialize() const override
3940 {
3941 std::stringstream ss;
3942 char *ref;
3943 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitType, ForwardLimitType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3944 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosEnable, ForwardLimitAutosetPositionEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3945 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosValue, ForwardLimitAutosetPositionValue.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3946 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitEnable, ForwardLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3947 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitSource, ForwardLimitSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3948 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitRemoteSensorID, ForwardLimitRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3949 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitType, ReverseLimitType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3950 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosEnable, ReverseLimitAutosetPositionEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3951 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosValue, ReverseLimitAutosetPositionValue.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
3952 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitEnable, ReverseLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3953 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitSource, ReverseLimitSource.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3954 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitRemoteSensorID, ReverseLimitRemoteSensorID, &ref); if (ref != nullptr) { ss << ref; free(ref); }
3955 return ss.str();
3956 }
3957
3958 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
3959 {
3960 const char *string_c_str = to_deserialize.c_str();
3961 size_t string_length = to_deserialize.length();
3962 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitType, string_c_str, string_length, &ForwardLimitType.value);
3963 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosEnable, string_c_str, string_length, &ForwardLimitAutosetPositionEnable);
3964 double ForwardLimitAutosetPositionValueVal = ForwardLimitAutosetPositionValue.to<double>();
3965 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitAutosetPosValue, string_c_str, string_length, &ForwardLimitAutosetPositionValueVal);
3966 ForwardLimitAutosetPositionValue = units::angle::turn_t{ForwardLimitAutosetPositionValueVal};
3967 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitEnable, string_c_str, string_length, &ForwardLimitEnable);
3968 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitSource, string_c_str, string_length, &ForwardLimitSource.value);
3969 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ForwardLimitRemoteSensorID, string_c_str, string_length, &ForwardLimitRemoteSensorID);
3970 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitType, string_c_str, string_length, &ReverseLimitType.value);
3971 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosEnable, string_c_str, string_length, &ReverseLimitAutosetPositionEnable);
3972 double ReverseLimitAutosetPositionValueVal = ReverseLimitAutosetPositionValue.to<double>();
3973 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitAutosetPosValue, string_c_str, string_length, &ReverseLimitAutosetPositionValueVal);
3974 ReverseLimitAutosetPositionValue = units::angle::turn_t{ReverseLimitAutosetPositionValueVal};
3975 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitEnable, string_c_str, string_length, &ReverseLimitEnable);
3976 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitSource, string_c_str, string_length, &ReverseLimitSource.value);
3977 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_ReverseLimitRemoteSensorID, string_c_str, string_length, &ReverseLimitRemoteSensorID);
3978 return 0;
3979 }
3980};
3981
3982
3983/**
3984 * \brief Configs that affect audible components of the device.
3985 *
3986 * \details Includes configuration for the beep on boot.
3987 */
3989{
3990public:
3991 constexpr AudioConfigs() = default;
3992
3993 /**
3994 * \brief If true, the TalonFX will beep during boot-up. This is
3995 * useful for general debugging, and defaults to true. If rotor is
3996 * moving during boot-up, the beep will not occur regardless of this
3997 * setting.
3998 *
3999 * - Default Value: True
4000 */
4001 bool BeepOnBoot = true;
4002 /**
4003 * \brief If true, the TalonFX will beep during configuration API
4004 * calls if device is disabled. This is useful for general debugging,
4005 * and defaults to true. Note that if the rotor is moving, the beep
4006 * will not occur regardless of this setting.
4007 *
4008 * - Default Value: True
4009 */
4010 bool BeepOnConfig = true;
4011 /**
4012 * \brief If true, the TalonFX will allow Orchestra and MusicTone
4013 * requests during disabled state. This can be used to address corner
4014 * cases when music features are needed when disabled. This setting
4015 * defaults to false. Note that if the rotor is moving, music
4016 * features are always disabled regardless of this setting.
4017 *
4018 * - Default Value: False
4019 */
4021
4022 /**
4023 * \brief Modifies this configuration's BeepOnBoot parameter and returns itself for
4024 * method-chaining and easier to use config API.
4025 *
4026 * If true, the TalonFX will beep during boot-up. This is useful for
4027 * general debugging, and defaults to true. If rotor is moving during
4028 * boot-up, the beep will not occur regardless of this setting.
4029 *
4030 * - Default Value: True
4031 *
4032 * \param newBeepOnBoot Parameter to modify
4033 * \returns Itself
4034 */
4035 constexpr AudioConfigs &WithBeepOnBoot(bool newBeepOnBoot)
4036 {
4037 BeepOnBoot = std::move(newBeepOnBoot);
4038 return *this;
4039 }
4040
4041 /**
4042 * \brief Modifies this configuration's BeepOnConfig parameter and returns itself for
4043 * method-chaining and easier to use config API.
4044 *
4045 * If true, the TalonFX will beep during configuration API calls if
4046 * device is disabled. This is useful for general debugging, and
4047 * defaults to true. Note that if the rotor is moving, the beep will
4048 * not occur regardless of this setting.
4049 *
4050 * - Default Value: True
4051 *
4052 * \param newBeepOnConfig Parameter to modify
4053 * \returns Itself
4054 */
4055 constexpr AudioConfigs &WithBeepOnConfig(bool newBeepOnConfig)
4056 {
4057 BeepOnConfig = std::move(newBeepOnConfig);
4058 return *this;
4059 }
4060
4061 /**
4062 * \brief Modifies this configuration's AllowMusicDurDisable parameter and returns itself for
4063 * method-chaining and easier to use config API.
4064 *
4065 * If true, the TalonFX will allow Orchestra and MusicTone requests
4066 * during disabled state. This can be used to address corner cases
4067 * when music features are needed when disabled. This setting
4068 * defaults to false. Note that if the rotor is moving, music
4069 * features are always disabled regardless of this setting.
4070 *
4071 * - Default Value: False
4072 *
4073 * \param newAllowMusicDurDisable Parameter to modify
4074 * \returns Itself
4075 */
4076 constexpr AudioConfigs &WithAllowMusicDurDisable(bool newAllowMusicDurDisable)
4077 {
4078 AllowMusicDurDisable = std::move(newAllowMusicDurDisable);
4079 return *this;
4080 }
4081
4082
4083
4084 std::string ToString() const override
4085 {
4086 std::stringstream ss;
4087 ss << "Config Group: Audio" << std::endl;
4088 ss << " BeepOnBoot: " << BeepOnBoot << std::endl;
4089 ss << " BeepOnConfig: " << BeepOnConfig << std::endl;
4090 ss << " AllowMusicDurDisable: " << AllowMusicDurDisable << std::endl;
4091 return ss.str();
4092 }
4093
4094 std::string Serialize() const override
4095 {
4096 std::stringstream ss;
4097 char *ref;
4098 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnBoot, BeepOnBoot, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4099 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnConfig, BeepOnConfig, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4100 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_AllowMusicDurDisable, AllowMusicDurDisable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4101 return ss.str();
4102 }
4103
4104 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4105 {
4106 const char *string_c_str = to_deserialize.c_str();
4107 size_t string_length = to_deserialize.length();
4108 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnBoot, string_c_str, string_length, &BeepOnBoot);
4109 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_BeepOnConfig, string_c_str, string_length, &BeepOnConfig);
4110 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_AllowMusicDurDisable, string_c_str, string_length, &AllowMusicDurDisable);
4111 return 0;
4112 }
4113};
4114
4115
4116/**
4117 * \brief Configs that affect how software-limit switches behave.
4118 *
4119 * \details Includes enabling software-limit switches and the
4120 * threshold at which they are tripped.
4121 */
4123{
4124public:
4125 constexpr SoftwareLimitSwitchConfigs() = default;
4126
4127 /**
4128 * \brief If enabled, the motor output is set to neutral if position
4129 * exceeds ForwardSoftLimitThreshold and forward output is requested.
4130 *
4131 * - Default Value: False
4132 */
4134 /**
4135 * \brief If enabled, the motor output is set to neutral if position
4136 * exceeds ReverseSoftLimitThreshold and reverse output is requested.
4137 *
4138 * - Default Value: False
4139 */
4141 /**
4142 * \brief Position threshold for forward soft limit features.
4143 * ForwardSoftLimitEnable must be enabled for this to take effect.
4144 *
4145 * - Minimum Value: -3.4e+38
4146 * - Maximum Value: 3.4e+38
4147 * - Default Value: 0
4148 * - Units: rotations
4149 */
4150 units::angle::turn_t ForwardSoftLimitThreshold = 0_tr;
4151 /**
4152 * \brief Position threshold for reverse soft limit features.
4153 * ReverseSoftLimitEnable must be enabled for this to take effect.
4154 *
4155 * - Minimum Value: -3.4e+38
4156 * - Maximum Value: 3.4e+38
4157 * - Default Value: 0
4158 * - Units: rotations
4159 */
4160 units::angle::turn_t ReverseSoftLimitThreshold = 0_tr;
4161
4162 /**
4163 * \brief Modifies this configuration's ForwardSoftLimitEnable parameter and returns itself for
4164 * method-chaining and easier to use config API.
4165 *
4166 * If enabled, the motor output is set to neutral if position exceeds
4167 * ForwardSoftLimitThreshold and forward output is requested.
4168 *
4169 * - Default Value: False
4170 *
4171 * \param newForwardSoftLimitEnable Parameter to modify
4172 * \returns Itself
4173 */
4174 constexpr SoftwareLimitSwitchConfigs &WithForwardSoftLimitEnable(bool newForwardSoftLimitEnable)
4175 {
4176 ForwardSoftLimitEnable = std::move(newForwardSoftLimitEnable);
4177 return *this;
4178 }
4179
4180 /**
4181 * \brief Modifies this configuration's ReverseSoftLimitEnable parameter and returns itself for
4182 * method-chaining and easier to use config API.
4183 *
4184 * If enabled, the motor output is set to neutral if position exceeds
4185 * ReverseSoftLimitThreshold and reverse output is requested.
4186 *
4187 * - Default Value: False
4188 *
4189 * \param newReverseSoftLimitEnable Parameter to modify
4190 * \returns Itself
4191 */
4192 constexpr SoftwareLimitSwitchConfigs &WithReverseSoftLimitEnable(bool newReverseSoftLimitEnable)
4193 {
4194 ReverseSoftLimitEnable = std::move(newReverseSoftLimitEnable);
4195 return *this;
4196 }
4197
4198 /**
4199 * \brief Modifies this configuration's ForwardSoftLimitThreshold parameter and returns itself for
4200 * method-chaining and easier to use config API.
4201 *
4202 * Position threshold for forward soft limit features.
4203 * ForwardSoftLimitEnable must be enabled for this to take effect.
4204 *
4205 * - Minimum Value: -3.4e+38
4206 * - Maximum Value: 3.4e+38
4207 * - Default Value: 0
4208 * - Units: rotations
4209 *
4210 * \param newForwardSoftLimitThreshold Parameter to modify
4211 * \returns Itself
4212 */
4213 constexpr SoftwareLimitSwitchConfigs &WithForwardSoftLimitThreshold(units::angle::turn_t newForwardSoftLimitThreshold)
4214 {
4215 ForwardSoftLimitThreshold = std::move(newForwardSoftLimitThreshold);
4216 return *this;
4217 }
4218
4219 /**
4220 * \brief Modifies this configuration's ReverseSoftLimitThreshold parameter and returns itself for
4221 * method-chaining and easier to use config API.
4222 *
4223 * Position threshold for reverse soft limit features.
4224 * ReverseSoftLimitEnable must be enabled for this to take effect.
4225 *
4226 * - Minimum Value: -3.4e+38
4227 * - Maximum Value: 3.4e+38
4228 * - Default Value: 0
4229 * - Units: rotations
4230 *
4231 * \param newReverseSoftLimitThreshold Parameter to modify
4232 * \returns Itself
4233 */
4234 constexpr SoftwareLimitSwitchConfigs &WithReverseSoftLimitThreshold(units::angle::turn_t newReverseSoftLimitThreshold)
4235 {
4236 ReverseSoftLimitThreshold = std::move(newReverseSoftLimitThreshold);
4237 return *this;
4238 }
4239
4240
4241
4242 std::string ToString() const override
4243 {
4244 std::stringstream ss;
4245 ss << "Config Group: SoftwareLimitSwitch" << std::endl;
4246 ss << " ForwardSoftLimitEnable: " << ForwardSoftLimitEnable << std::endl;
4247 ss << " ReverseSoftLimitEnable: " << ReverseSoftLimitEnable << std::endl;
4248 ss << " ForwardSoftLimitThreshold: " << ForwardSoftLimitThreshold.to<double>() << " rotations" << std::endl;
4249 ss << " ReverseSoftLimitThreshold: " << ReverseSoftLimitThreshold.to<double>() << " rotations" << std::endl;
4250 return ss.str();
4251 }
4252
4253 std::string Serialize() const override
4254 {
4255 std::stringstream ss;
4256 char *ref;
4257 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitEnable, ForwardSoftLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4258 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitEnable, ReverseSoftLimitEnable, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4259 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitThreshold, ForwardSoftLimitThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4260 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitThreshold, ReverseSoftLimitThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4261 return ss.str();
4262 }
4263
4264 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4265 {
4266 const char *string_c_str = to_deserialize.c_str();
4267 size_t string_length = to_deserialize.length();
4268 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitEnable, string_c_str, string_length, &ForwardSoftLimitEnable);
4269 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitEnable, string_c_str, string_length, &ReverseSoftLimitEnable);
4270 double ForwardSoftLimitThresholdVal = ForwardSoftLimitThreshold.to<double>();
4271 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ForwardSoftLimitThreshold, string_c_str, string_length, &ForwardSoftLimitThresholdVal);
4272 ForwardSoftLimitThreshold = units::angle::turn_t{ForwardSoftLimitThresholdVal};
4273 double ReverseSoftLimitThresholdVal = ReverseSoftLimitThreshold.to<double>();
4274 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_ReverseSoftLimitThreshold, string_c_str, string_length, &ReverseSoftLimitThresholdVal);
4275 ReverseSoftLimitThreshold = units::angle::turn_t{ReverseSoftLimitThresholdVal};
4276 return 0;
4277 }
4278};
4279
4280
4281/**
4282 * \brief Configs for Motion Magic®.
4283 *
4284 * \details Includes Velocity, Acceleration, Jerk, and Expo
4285 * parameters.
4286 */
4288{
4289public:
4290 constexpr MotionMagicConfigs() = default;
4291
4292 /**
4293 * \brief This is the maximum velocity Motion Magic® based control
4294 * modes are allowed to use. Motion Magic® Velocity control modes do
4295 * not use this config.
4296 *
4297 * When using Motion Magic® Expo control modes, setting this to 0 will
4298 * allow the profile to run to the max possible velocity based on
4299 * Expo_kV.
4300 *
4301 * - Minimum Value: 0
4302 * - Maximum Value: 9999
4303 * - Default Value: 0
4304 * - Units: rot per sec
4305 */
4306 units::angular_velocity::turns_per_second_t MotionMagicCruiseVelocity = 0_tps;
4307 /**
4308 * \brief This is the target acceleration Motion Magic® based control
4309 * modes are allowed to use. Motion Magic® Expo control modes do not
4310 * use this config.
4311 *
4312 * - Minimum Value: 0
4313 * - Maximum Value: 9999
4314 * - Default Value: 0
4315 * - Units: rot per sec²
4316 */
4317 units::angular_acceleration::turns_per_second_squared_t MotionMagicAcceleration = 0_tr_per_s_sq;
4318 /**
4319 * \brief This is the target jerk (acceleration derivative) Motion
4320 * Magic® based control modes are allowed to use. Motion Magic® Expo
4321 * control modes do not use this config. This allows Motion Magic® to
4322 * generate S-Curve profiles.
4323 *
4324 * Jerk is optional; if this is set to zero, then Motion Magic® will
4325 * not apply a Jerk limit.
4326 *
4327 * - Minimum Value: 0
4328 * - Maximum Value: 9999
4329 * - Default Value: 0
4330 * - Units: rot per sec³
4331 */
4332 units::angular_jerk::turns_per_second_cubed_t MotionMagicJerk = 0_tr_per_s_cu;
4333 /**
4334 * \brief This is the target kV used only by Motion Magic® Expo
4335 * control modes. Unlike the kV slot gain, this is always in units of
4336 * V/rps.
4337 *
4338 * This represents the amount of voltage necessary to hold a velocity.
4339 * In terms of the Motion Magic® Expo profile, a higher kV results in
4340 * a slower maximum velocity.
4341 *
4342 * - Minimum Value: 0.001
4343 * - Maximum Value: 100
4344 * - Default Value: 0.12
4345 * - Units: V/rps
4346 */
4347 ctre::unit::volts_per_turn_per_second_t MotionMagicExpo_kV = 0.12_V / 1_tps;
4348 /**
4349 * \brief This is the target kA used only by Motion Magic® Expo
4350 * control modes. Unlike the kA slot gain, this is always in units of
4351 * V/rps².
4352 *
4353 * This represents the amount of voltage necessary to achieve an
4354 * acceleration. In terms of the Motion Magic® Expo profile, a higher
4355 * kA results in a slower acceleration.
4356 *
4357 * - Minimum Value: 1e-05
4358 * - Maximum Value: 100
4359 * - Default Value: 0.1
4360 * - Units: V/rps²
4361 */
4362 ctre::unit::volts_per_turn_per_second_squared_t MotionMagicExpo_kA = 0.1_V / 1_tr_per_s_sq;
4363
4364 /**
4365 * \brief Modifies this configuration's MotionMagicCruiseVelocity parameter and returns itself for
4366 * method-chaining and easier to use config API.
4367 *
4368 * This is the maximum velocity Motion Magic® based control modes are
4369 * allowed to use. Motion Magic® Velocity control modes do not use
4370 * this config.
4371 *
4372 * When using Motion Magic® Expo control modes, setting this to 0 will
4373 * allow the profile to run to the max possible velocity based on
4374 * Expo_kV.
4375 *
4376 * - Minimum Value: 0
4377 * - Maximum Value: 9999
4378 * - Default Value: 0
4379 * - Units: rot per sec
4380 *
4381 * \param newMotionMagicCruiseVelocity Parameter to modify
4382 * \returns Itself
4383 */
4384 constexpr MotionMagicConfigs &WithMotionMagicCruiseVelocity(units::angular_velocity::turns_per_second_t newMotionMagicCruiseVelocity)
4385 {
4386 MotionMagicCruiseVelocity = std::move(newMotionMagicCruiseVelocity);
4387 return *this;
4388 }
4389
4390 /**
4391 * \brief Modifies this configuration's MotionMagicAcceleration parameter and returns itself for
4392 * method-chaining and easier to use config API.
4393 *
4394 * This is the target acceleration Motion Magic® based control modes
4395 * are allowed to use. Motion Magic® Expo control modes do not use
4396 * this config.
4397 *
4398 * - Minimum Value: 0
4399 * - Maximum Value: 9999
4400 * - Default Value: 0
4401 * - Units: rot per sec²
4402 *
4403 * \param newMotionMagicAcceleration Parameter to modify
4404 * \returns Itself
4405 */
4406 constexpr MotionMagicConfigs &WithMotionMagicAcceleration(units::angular_acceleration::turns_per_second_squared_t newMotionMagicAcceleration)
4407 {
4408 MotionMagicAcceleration = std::move(newMotionMagicAcceleration);
4409 return *this;
4410 }
4411
4412 /**
4413 * \brief Modifies this configuration's MotionMagicJerk parameter and returns itself for
4414 * method-chaining and easier to use config API.
4415 *
4416 * This is the target jerk (acceleration derivative) Motion Magic®
4417 * based control modes are allowed to use. Motion Magic® Expo control
4418 * modes do not use this config. This allows Motion Magic® to
4419 * generate S-Curve profiles.
4420 *
4421 * Jerk is optional; if this is set to zero, then Motion Magic® will
4422 * not apply a Jerk limit.
4423 *
4424 * - Minimum Value: 0
4425 * - Maximum Value: 9999
4426 * - Default Value: 0
4427 * - Units: rot per sec³
4428 *
4429 * \param newMotionMagicJerk Parameter to modify
4430 * \returns Itself
4431 */
4432 constexpr MotionMagicConfigs &WithMotionMagicJerk(units::angular_jerk::turns_per_second_cubed_t newMotionMagicJerk)
4433 {
4434 MotionMagicJerk = std::move(newMotionMagicJerk);
4435 return *this;
4436 }
4437
4438 /**
4439 * \brief Modifies this configuration's MotionMagicExpo_kV parameter and returns itself for
4440 * method-chaining and easier to use config API.
4441 *
4442 * This is the target kV used only by Motion Magic® Expo control
4443 * modes. Unlike the kV slot gain, this is always in units of V/rps.
4444 *
4445 * This represents the amount of voltage necessary to hold a velocity.
4446 * In terms of the Motion Magic® Expo profile, a higher kV results in
4447 * a slower maximum velocity.
4448 *
4449 * - Minimum Value: 0.001
4450 * - Maximum Value: 100
4451 * - Default Value: 0.12
4452 * - Units: V/rps
4453 *
4454 * \param newMotionMagicExpo_kV Parameter to modify
4455 * \returns Itself
4456 */
4457 constexpr MotionMagicConfigs &WithMotionMagicExpo_kV(ctre::unit::volts_per_turn_per_second_t newMotionMagicExpo_kV)
4458 {
4459 MotionMagicExpo_kV = std::move(newMotionMagicExpo_kV);
4460 return *this;
4461 }
4462
4463 /**
4464 * \brief Modifies this configuration's MotionMagicExpo_kA parameter and returns itself for
4465 * method-chaining and easier to use config API.
4466 *
4467 * This is the target kA used only by Motion Magic® Expo control
4468 * modes. Unlike the kA slot gain, this is always in units of V/rps².
4469 *
4470 * This represents the amount of voltage necessary to achieve an
4471 * acceleration. In terms of the Motion Magic® Expo profile, a higher
4472 * kA results in a slower acceleration.
4473 *
4474 * - Minimum Value: 1e-05
4475 * - Maximum Value: 100
4476 * - Default Value: 0.1
4477 * - Units: V/rps²
4478 *
4479 * \param newMotionMagicExpo_kA Parameter to modify
4480 * \returns Itself
4481 */
4482 constexpr MotionMagicConfigs &WithMotionMagicExpo_kA(ctre::unit::volts_per_turn_per_second_squared_t newMotionMagicExpo_kA)
4483 {
4484 MotionMagicExpo_kA = std::move(newMotionMagicExpo_kA);
4485 return *this;
4486 }
4487
4488
4489
4490 std::string ToString() const override
4491 {
4492 std::stringstream ss;
4493 ss << "Config Group: MotionMagic" << std::endl;
4494 ss << " MotionMagicCruiseVelocity: " << MotionMagicCruiseVelocity.to<double>() << " rot per sec" << std::endl;
4495 ss << " MotionMagicAcceleration: " << MotionMagicAcceleration.to<double>() << " rot per sec²" << std::endl;
4496 ss << " MotionMagicJerk: " << MotionMagicJerk.to<double>() << " rot per sec³" << std::endl;
4497 ss << " MotionMagicExpo_kV: " << MotionMagicExpo_kV.to<double>() << " V/rps" << std::endl;
4498 ss << " MotionMagicExpo_kA: " << MotionMagicExpo_kA.to<double>() << " V/rps²" << std::endl;
4499 return ss.str();
4500 }
4501
4502 std::string Serialize() const override
4503 {
4504 std::stringstream ss;
4505 char *ref;
4506 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicCruiseVelocity, MotionMagicCruiseVelocity.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4507 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicAcceleration, MotionMagicAcceleration.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4508 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicJerk, MotionMagicJerk.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4509 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kV, MotionMagicExpo_kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4510 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kA, MotionMagicExpo_kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4511 return ss.str();
4512 }
4513
4514 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4515 {
4516 const char *string_c_str = to_deserialize.c_str();
4517 size_t string_length = to_deserialize.length();
4518 double MotionMagicCruiseVelocityVal = MotionMagicCruiseVelocity.to<double>();
4519 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicCruiseVelocity, string_c_str, string_length, &MotionMagicCruiseVelocityVal);
4520 MotionMagicCruiseVelocity = units::angular_velocity::turns_per_second_t{MotionMagicCruiseVelocityVal};
4521 double MotionMagicAccelerationVal = MotionMagicAcceleration.to<double>();
4522 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicAcceleration, string_c_str, string_length, &MotionMagicAccelerationVal);
4523 MotionMagicAcceleration = units::angular_acceleration::turns_per_second_squared_t{MotionMagicAccelerationVal};
4524 double MotionMagicJerkVal = MotionMagicJerk.to<double>();
4525 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicJerk, string_c_str, string_length, &MotionMagicJerkVal);
4526 MotionMagicJerk = units::angular_jerk::turns_per_second_cubed_t{MotionMagicJerkVal};
4527 double MotionMagicExpo_kVVal = MotionMagicExpo_kV.to<double>();
4528 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kV, string_c_str, string_length, &MotionMagicExpo_kVVal);
4529 MotionMagicExpo_kV = ctre::unit::volts_per_turn_per_second_t{MotionMagicExpo_kVVal};
4530 double MotionMagicExpo_kAVal = MotionMagicExpo_kA.to<double>();
4531 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_MotionMagicExpo_kA, string_c_str, string_length, &MotionMagicExpo_kAVal);
4532 MotionMagicExpo_kA = ctre::unit::volts_per_turn_per_second_squared_t{MotionMagicExpo_kAVal};
4533 return 0;
4534 }
4535};
4536
4537
4538/**
4539 * \brief Custom Params.
4540 *
4541 * \details Custom paramaters that have no real impact on controller.
4542 */
4544{
4545public:
4546 constexpr CustomParamsConfigs() = default;
4547
4548 /**
4549 * \brief Custom parameter 0. This is provided to allow
4550 * end-applications to store persistent information in the device.
4551 *
4552 * - Minimum Value: -32768
4553 * - Maximum Value: 32767
4554 * - Default Value: 0
4555 * - Units:
4556 */
4558 /**
4559 * \brief Custom parameter 1. This is provided to allow
4560 * end-applications to store persistent information in the device.
4561 *
4562 * - Minimum Value: -32768
4563 * - Maximum Value: 32767
4564 * - Default Value: 0
4565 * - Units:
4566 */
4568
4569 /**
4570 * \brief Modifies this configuration's CustomParam0 parameter and returns itself for
4571 * method-chaining and easier to use config API.
4572 *
4573 * Custom parameter 0. This is provided to allow end-applications to
4574 * store persistent information in the device.
4575 *
4576 * - Minimum Value: -32768
4577 * - Maximum Value: 32767
4578 * - Default Value: 0
4579 * - Units:
4580 *
4581 * \param newCustomParam0 Parameter to modify
4582 * \returns Itself
4583 */
4584 constexpr CustomParamsConfigs &WithCustomParam0(int newCustomParam0)
4585 {
4586 CustomParam0 = std::move(newCustomParam0);
4587 return *this;
4588 }
4589
4590 /**
4591 * \brief Modifies this configuration's CustomParam1 parameter and returns itself for
4592 * method-chaining and easier to use config API.
4593 *
4594 * Custom parameter 1. This is provided to allow end-applications to
4595 * store persistent information in the device.
4596 *
4597 * - Minimum Value: -32768
4598 * - Maximum Value: 32767
4599 * - Default Value: 0
4600 * - Units:
4601 *
4602 * \param newCustomParam1 Parameter to modify
4603 * \returns Itself
4604 */
4605 constexpr CustomParamsConfigs &WithCustomParam1(int newCustomParam1)
4606 {
4607 CustomParam1 = std::move(newCustomParam1);
4608 return *this;
4609 }
4610
4611
4612
4613 std::string ToString() const override
4614 {
4615 std::stringstream ss;
4616 ss << "Config Group: CustomParams" << std::endl;
4617 ss << " CustomParam0: " << CustomParam0 << std::endl;
4618 ss << " CustomParam1: " << CustomParam1 << std::endl;
4619 return ss.str();
4620 }
4621
4622 std::string Serialize() const override
4623 {
4624 std::stringstream ss;
4625 char *ref;
4626 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CustomParam0, CustomParam0, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4627 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CustomParam1, CustomParam1, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4628 return ss.str();
4629 }
4630
4631 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4632 {
4633 const char *string_c_str = to_deserialize.c_str();
4634 size_t string_length = to_deserialize.length();
4635 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CustomParam0, string_c_str, string_length, &CustomParam0);
4636 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CustomParam1, string_c_str, string_length, &CustomParam1);
4637 return 0;
4638 }
4639};
4640
4641
4642/**
4643 * \brief Configs that affect general behavior during closed-looping.
4644 *
4645 * \details Includes Continuous Wrap features.
4646 */
4648{
4649public:
4650 constexpr ClosedLoopGeneralConfigs() = default;
4651
4652 /**
4653 * \brief Wrap position error within [-0.5,+0.5) mechanism rotations.
4654 * Typically used for continuous position closed-loops like swerve
4655 * azimuth.
4656 *
4657 * \details This uses the mechanism rotation value. If there is a gear
4658 * ratio between the sensor and the mechanism, make sure to apply a
4659 * SensorToMechanismRatio so the closed loop operates on the full
4660 * rotation.
4661 *
4662 * - Default Value: False
4663 */
4664 bool ContinuousWrap = false;
4665
4666 /**
4667 * \brief Modifies this configuration's ContinuousWrap parameter and returns itself for
4668 * method-chaining and easier to use config API.
4669 *
4670 * Wrap position error within [-0.5,+0.5) mechanism rotations.
4671 * Typically used for continuous position closed-loops like swerve
4672 * azimuth.
4673 *
4674 * \details This uses the mechanism rotation value. If there is a gear
4675 * ratio between the sensor and the mechanism, make sure to apply a
4676 * SensorToMechanismRatio so the closed loop operates on the full
4677 * rotation.
4678 *
4679 * - Default Value: False
4680 *
4681 * \param newContinuousWrap Parameter to modify
4682 * \returns Itself
4683 */
4684 constexpr ClosedLoopGeneralConfigs &WithContinuousWrap(bool newContinuousWrap)
4685 {
4686 ContinuousWrap = std::move(newContinuousWrap);
4687 return *this;
4688 }
4689
4690
4691
4692 std::string ToString() const override
4693 {
4694 std::stringstream ss;
4695 ss << "Config Group: ClosedLoopGeneral" << std::endl;
4696 ss << " ContinuousWrap: " << ContinuousWrap << std::endl;
4697 return ss.str();
4698 }
4699
4700 std::string Serialize() const override
4701 {
4702 std::stringstream ss;
4703 char *ref;
4704 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_ContinuousWrap, ContinuousWrap, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4705 return ss.str();
4706 }
4707
4708 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4709 {
4710 const char *string_c_str = to_deserialize.c_str();
4711 size_t string_length = to_deserialize.length();
4712 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_ContinuousWrap, string_c_str, string_length, &ContinuousWrap);
4713 return 0;
4714 }
4715};
4716
4717
4718/**
4719 * \brief Configs that affect the ToF sensor
4720 *
4721 * \details Includes Update mode and frequency
4722 */
4724{
4725public:
4726 constexpr ToFParamsConfigs() = default;
4727
4728 /**
4729 * \brief Update mode of the CANrange. The CANrange supports
4730 * short-range and long-range detection at various update frequencies.
4731 *
4732 */
4734 /**
4735 * \brief Rate at which the CANrange will take measurements. A lower
4736 * frequency may provide more stable readings but will reduce the data
4737 * rate of the sensor.
4738 *
4739 * - Minimum Value: 5
4740 * - Maximum Value: 50
4741 * - Default Value: 50
4742 * - Units: Hz
4743 */
4744 units::frequency::hertz_t UpdateFrequency = 50_Hz;
4745
4746 /**
4747 * \brief Modifies this configuration's UpdateMode parameter and returns itself for
4748 * method-chaining and easier to use config API.
4749 *
4750 * Update mode of the CANrange. The CANrange supports short-range and
4751 * long-range detection at various update frequencies.
4752 *
4753 *
4754 * \param newUpdateMode Parameter to modify
4755 * \returns Itself
4756 */
4758 {
4759 UpdateMode = std::move(newUpdateMode);
4760 return *this;
4761 }
4762
4763 /**
4764 * \brief Modifies this configuration's UpdateFrequency parameter and returns itself for
4765 * method-chaining and easier to use config API.
4766 *
4767 * Rate at which the CANrange will take measurements. A lower
4768 * frequency may provide more stable readings but will reduce the data
4769 * rate of the sensor.
4770 *
4771 * - Minimum Value: 5
4772 * - Maximum Value: 50
4773 * - Default Value: 50
4774 * - Units: Hz
4775 *
4776 * \param newUpdateFrequency Parameter to modify
4777 * \returns Itself
4778 */
4779 constexpr ToFParamsConfigs &WithUpdateFrequency(units::frequency::hertz_t newUpdateFrequency)
4780 {
4781 UpdateFrequency = std::move(newUpdateFrequency);
4782 return *this;
4783 }
4784
4785
4786
4787 std::string ToString() const override
4788 {
4789 std::stringstream ss;
4790 ss << "Config Group: ToFParams" << std::endl;
4791 ss << " UpdateMode: " << UpdateMode << std::endl;
4792 ss << " UpdateFrequency: " << UpdateFrequency.to<double>() << " Hz" << std::endl;
4793 return ss.str();
4794 }
4795
4796 std::string Serialize() const override
4797 {
4798 std::stringstream ss;
4799 char *ref;
4800 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANrange_UpdateMode, UpdateMode.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
4801 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_UpdateFreq, UpdateFrequency.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4802 return ss.str();
4803 }
4804
4805 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4806 {
4807 const char *string_c_str = to_deserialize.c_str();
4808 size_t string_length = to_deserialize.length();
4809 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANrange_UpdateMode, string_c_str, string_length, &UpdateMode.value);
4810 double UpdateFrequencyVal = UpdateFrequency.to<double>();
4811 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_UpdateFreq, string_c_str, string_length, &UpdateFrequencyVal);
4812 UpdateFrequency = units::frequency::hertz_t{UpdateFrequencyVal};
4813 return 0;
4814 }
4815};
4816
4817
4818/**
4819 * \brief Configs that affect the ToF Proximity detection
4820 *
4821 * \details Includes proximity mode and the threshold for simple
4822 * detection
4823 */
4825{
4826public:
4827 constexpr ProximityParamsConfigs() = default;
4828
4829 /**
4830 * \brief Threshold for object detection.
4831 *
4832 * - Minimum Value: 0
4833 * - Maximum Value: 4
4834 * - Default Value: 0.4
4835 * - Units: m
4836 */
4837 units::length::meter_t ProximityThreshold = 0.4_m;
4838 /**
4839 * \brief How far above and below the threshold the distance needs to
4840 * be to trigger undetected and detected, respectively. This is used
4841 * to prevent bouncing between the detected and undetected states for
4842 * objects on the threshold.
4843 *
4844 * If the threshold is set to 0.1 meters, and the hysteresis is 0.01
4845 * meters, then an object needs to be within 0.09 meters to be
4846 * detected. After the object is first detected, the distance then
4847 * needs to exceed 0.11 meters to become undetected again.
4848 *
4849 * - Minimum Value: 0
4850 * - Maximum Value: 1
4851 * - Default Value: 0.01
4852 * - Units: m
4853 */
4854 units::length::meter_t ProximityHysteresis = 0.01_m;
4855 /**
4856 * \brief The minimum allowable signal strength before determining the
4857 * measurement is valid.
4858 *
4859 * If the signal strength is particularly low, this typically means
4860 * the object is far away and there's fewer total samples to derive
4861 * the distance from. Set this value to be below the lowest strength
4862 * you see when you're detecting an object with the CANrange; the
4863 * default of 2500 is typically acceptable in most cases.
4864 *
4865 * - Minimum Value: 1
4866 * - Maximum Value: 15000
4867 * - Default Value: 2500
4868 * - Units:
4869 */
4870 units::dimensionless::scalar_t MinSignalStrengthForValidMeasurement = 2500;
4871
4872 /**
4873 * \brief Modifies this configuration's ProximityThreshold parameter and returns itself for
4874 * method-chaining and easier to use config API.
4875 *
4876 * Threshold for object detection.
4877 *
4878 * - Minimum Value: 0
4879 * - Maximum Value: 4
4880 * - Default Value: 0.4
4881 * - Units: m
4882 *
4883 * \param newProximityThreshold Parameter to modify
4884 * \returns Itself
4885 */
4886 constexpr ProximityParamsConfigs &WithProximityThreshold(units::length::meter_t newProximityThreshold)
4887 {
4888 ProximityThreshold = std::move(newProximityThreshold);
4889 return *this;
4890 }
4891
4892 /**
4893 * \brief Modifies this configuration's ProximityHysteresis parameter and returns itself for
4894 * method-chaining and easier to use config API.
4895 *
4896 * How far above and below the threshold the distance needs to be to
4897 * trigger undetected and detected, respectively. This is used to
4898 * prevent bouncing between the detected and undetected states for
4899 * objects on the threshold.
4900 *
4901 * If the threshold is set to 0.1 meters, and the hysteresis is 0.01
4902 * meters, then an object needs to be within 0.09 meters to be
4903 * detected. After the object is first detected, the distance then
4904 * needs to exceed 0.11 meters to become undetected again.
4905 *
4906 * - Minimum Value: 0
4907 * - Maximum Value: 1
4908 * - Default Value: 0.01
4909 * - Units: m
4910 *
4911 * \param newProximityHysteresis Parameter to modify
4912 * \returns Itself
4913 */
4914 constexpr ProximityParamsConfigs &WithProximityHysteresis(units::length::meter_t newProximityHysteresis)
4915 {
4916 ProximityHysteresis = std::move(newProximityHysteresis);
4917 return *this;
4918 }
4919
4920 /**
4921 * \brief Modifies this configuration's MinSignalStrengthForValidMeasurement parameter and returns itself for
4922 * method-chaining and easier to use config API.
4923 *
4924 * The minimum allowable signal strength before determining the
4925 * measurement is valid.
4926 *
4927 * If the signal strength is particularly low, this typically means
4928 * the object is far away and there's fewer total samples to derive
4929 * the distance from. Set this value to be below the lowest strength
4930 * you see when you're detecting an object with the CANrange; the
4931 * default of 2500 is typically acceptable in most cases.
4932 *
4933 * - Minimum Value: 1
4934 * - Maximum Value: 15000
4935 * - Default Value: 2500
4936 * - Units:
4937 *
4938 * \param newMinSignalStrengthForValidMeasurement Parameter to modify
4939 * \returns Itself
4940 */
4941 constexpr ProximityParamsConfigs &WithMinSignalStrengthForValidMeasurement(units::dimensionless::scalar_t newMinSignalStrengthForValidMeasurement)
4942 {
4943 MinSignalStrengthForValidMeasurement = std::move(newMinSignalStrengthForValidMeasurement);
4944 return *this;
4945 }
4946
4947
4948
4949 std::string ToString() const override
4950 {
4951 std::stringstream ss;
4952 ss << "Config Group: ProximityParams" << std::endl;
4953 ss << " ProximityThreshold: " << ProximityThreshold.to<double>() << " m" << std::endl;
4954 ss << " ProximityHysteresis: " << ProximityHysteresis.to<double>() << " m" << std::endl;
4955 ss << " MinSignalStrengthForValidMeasurement: " << MinSignalStrengthForValidMeasurement.to<double>() << std::endl;
4956 return ss.str();
4957 }
4958
4959 std::string Serialize() const override
4960 {
4961 std::stringstream ss;
4962 char *ref;
4963 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityThreshold, ProximityThreshold.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4964 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityHysteresis, ProximityHysteresis.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4965 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_MinSigStrengthForValidMeas, MinSignalStrengthForValidMeasurement.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
4966 return ss.str();
4967 }
4968
4969 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
4970 {
4971 const char *string_c_str = to_deserialize.c_str();
4972 size_t string_length = to_deserialize.length();
4973 double ProximityThresholdVal = ProximityThreshold.to<double>();
4974 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityThreshold, string_c_str, string_length, &ProximityThresholdVal);
4975 ProximityThreshold = units::length::meter_t{ProximityThresholdVal};
4976 double ProximityHysteresisVal = ProximityHysteresis.to<double>();
4977 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_ProximityHysteresis, string_c_str, string_length, &ProximityHysteresisVal);
4978 ProximityHysteresis = units::length::meter_t{ProximityHysteresisVal};
4979 double MinSignalStrengthForValidMeasurementVal = MinSignalStrengthForValidMeasurement.to<double>();
4980 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_MinSigStrengthForValidMeas, string_c_str, string_length, &MinSignalStrengthForValidMeasurementVal);
4981 MinSignalStrengthForValidMeasurement = units::dimensionless::scalar_t{MinSignalStrengthForValidMeasurementVal};
4982 return 0;
4983 }
4984};
4985
4986
4987/**
4988 * \brief Configs that affect the ToF Field of View
4989 *
4990 * \details Includes range and center configs
4991 */
4993{
4994public:
4995 constexpr FovParamsConfigs() = default;
4996
4997 /**
4998 * \brief Specifies the target center of the Field of View in the X
4999 * direction.
5000 *
5001 * \details The exact value may be different for different CANrange
5002 * devices due to imperfections in the sensing silicon.
5003 *
5004 * - Minimum Value: -11.8
5005 * - Maximum Value: 11.8
5006 * - Default Value: 0
5007 * - Units: deg
5008 */
5009 units::angle::degree_t FOVCenterX = 0_deg;
5010 /**
5011 * \brief Specifies the target center of the Field of View in the Y
5012 * direction.
5013 *
5014 * \details The exact value may be different for different CANrange
5015 * devices due to imperfections in the sensing silicon.
5016 *
5017 * - Minimum Value: -11.8
5018 * - Maximum Value: 11.8
5019 * - Default Value: 0
5020 * - Units: deg
5021 */
5022 units::angle::degree_t FOVCenterY = 0_deg;
5023 /**
5024 * \brief Specifies the target range of the Field of View in the X
5025 * direction. This is the full range of the FOV.
5026 *
5027 * The magnitude of this is capped to abs(27 - 2*FOVCenterX).
5028 *
5029 * \details The exact value may be different for different CANrange
5030 * devices due to imperfections in the sensing silicon.
5031 *
5032 * - Minimum Value: 6.75
5033 * - Maximum Value: 27
5034 * - Default Value: 27
5035 * - Units: deg
5036 */
5037 units::angle::degree_t FOVRangeX = 27_deg;
5038 /**
5039 * \brief Specifies the target range of the Field of View in the Y
5040 * direction. This is the full range of the FOV.
5041 *
5042 * The magnitude of this is capped to abs(27 - 2*FOVCenterY).
5043 *
5044 * \details The exact value may be different for different CANrange
5045 * devices due to imperfections in the sensing silicon.
5046 *
5047 * - Minimum Value: 6.75
5048 * - Maximum Value: 27
5049 * - Default Value: 27
5050 * - Units: deg
5051 */
5052 units::angle::degree_t FOVRangeY = 27_deg;
5053
5054 /**
5055 * \brief Modifies this configuration's FOVCenterX parameter and returns itself for
5056 * method-chaining and easier to use config API.
5057 *
5058 * Specifies the target center of the Field of View in the X
5059 * direction.
5060 *
5061 * \details The exact value may be different for different CANrange
5062 * devices due to imperfections in the sensing silicon.
5063 *
5064 * - Minimum Value: -11.8
5065 * - Maximum Value: 11.8
5066 * - Default Value: 0
5067 * - Units: deg
5068 *
5069 * \param newFOVCenterX Parameter to modify
5070 * \returns Itself
5071 */
5072 constexpr FovParamsConfigs &WithFOVCenterX(units::angle::degree_t newFOVCenterX)
5073 {
5074 FOVCenterX = std::move(newFOVCenterX);
5075 return *this;
5076 }
5077
5078 /**
5079 * \brief Modifies this configuration's FOVCenterY parameter and returns itself for
5080 * method-chaining and easier to use config API.
5081 *
5082 * Specifies the target center of the Field of View in the Y
5083 * direction.
5084 *
5085 * \details The exact value may be different for different CANrange
5086 * devices due to imperfections in the sensing silicon.
5087 *
5088 * - Minimum Value: -11.8
5089 * - Maximum Value: 11.8
5090 * - Default Value: 0
5091 * - Units: deg
5092 *
5093 * \param newFOVCenterY Parameter to modify
5094 * \returns Itself
5095 */
5096 constexpr FovParamsConfigs &WithFOVCenterY(units::angle::degree_t newFOVCenterY)
5097 {
5098 FOVCenterY = std::move(newFOVCenterY);
5099 return *this;
5100 }
5101
5102 /**
5103 * \brief Modifies this configuration's FOVRangeX parameter and returns itself for
5104 * method-chaining and easier to use config API.
5105 *
5106 * Specifies the target range of the Field of View in the X direction.
5107 * This is the full range of the FOV.
5108 *
5109 * The magnitude of this is capped to abs(27 - 2*FOVCenterX).
5110 *
5111 * \details The exact value may be different for different CANrange
5112 * devices due to imperfections in the sensing silicon.
5113 *
5114 * - Minimum Value: 6.75
5115 * - Maximum Value: 27
5116 * - Default Value: 27
5117 * - Units: deg
5118 *
5119 * \param newFOVRangeX Parameter to modify
5120 * \returns Itself
5121 */
5122 constexpr FovParamsConfigs &WithFOVRangeX(units::angle::degree_t newFOVRangeX)
5123 {
5124 FOVRangeX = std::move(newFOVRangeX);
5125 return *this;
5126 }
5127
5128 /**
5129 * \brief Modifies this configuration's FOVRangeY parameter and returns itself for
5130 * method-chaining and easier to use config API.
5131 *
5132 * Specifies the target range of the Field of View in the Y direction.
5133 * This is the full range of the FOV.
5134 *
5135 * The magnitude of this is capped to abs(27 - 2*FOVCenterY).
5136 *
5137 * \details The exact value may be different for different CANrange
5138 * devices due to imperfections in the sensing silicon.
5139 *
5140 * - Minimum Value: 6.75
5141 * - Maximum Value: 27
5142 * - Default Value: 27
5143 * - Units: deg
5144 *
5145 * \param newFOVRangeY Parameter to modify
5146 * \returns Itself
5147 */
5148 constexpr FovParamsConfigs &WithFOVRangeY(units::angle::degree_t newFOVRangeY)
5149 {
5150 FOVRangeY = std::move(newFOVRangeY);
5151 return *this;
5152 }
5153
5154
5155
5156 std::string ToString() const override
5157 {
5158 std::stringstream ss;
5159 ss << "Config Group: FovParams" << std::endl;
5160 ss << " FOVCenterX: " << FOVCenterX.to<double>() << " deg" << std::endl;
5161 ss << " FOVCenterY: " << FOVCenterY.to<double>() << " deg" << std::endl;
5162 ss << " FOVRangeX: " << FOVRangeX.to<double>() << " deg" << std::endl;
5163 ss << " FOVRangeY: " << FOVRangeY.to<double>() << " deg" << std::endl;
5164 return ss.str();
5165 }
5166
5167 std::string Serialize() const override
5168 {
5169 std::stringstream ss;
5170 char *ref;
5171 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterX, FOVCenterX.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5172 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterY, FOVCenterY.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5173 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeX, FOVRangeX.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5174 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeY, FOVRangeY.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5175 return ss.str();
5176 }
5177
5178 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5179 {
5180 const char *string_c_str = to_deserialize.c_str();
5181 size_t string_length = to_deserialize.length();
5182 double FOVCenterXVal = FOVCenterX.to<double>();
5183 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterX, string_c_str, string_length, &FOVCenterXVal);
5184 FOVCenterX = units::angle::degree_t{FOVCenterXVal};
5185 double FOVCenterYVal = FOVCenterY.to<double>();
5186 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVCenterY, string_c_str, string_length, &FOVCenterYVal);
5187 FOVCenterY = units::angle::degree_t{FOVCenterYVal};
5188 double FOVRangeXVal = FOVRangeX.to<double>();
5189 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeX, string_c_str, string_length, &FOVRangeXVal);
5190 FOVRangeX = units::angle::degree_t{FOVRangeXVal};
5191 double FOVRangeYVal = FOVRangeY.to<double>();
5192 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::CANrange_FOVRangeY, string_c_str, string_length, &FOVRangeYVal);
5193 FOVRangeY = units::angle::degree_t{FOVRangeYVal};
5194 return 0;
5195 }
5196};
5197
5198
5199/**
5200 * \brief Configs that determine motor selection and commutation.
5201 *
5202 * \details Set these configs to match your motor setup before
5203 * commanding motor output.
5204 */
5206{
5207public:
5208 constexpr CommutationConfigs() = default;
5209
5210 /**
5211 * \brief Requires Phoenix Pro; Improves commutation and velocity
5212 * measurement for motors with hall sensors. Talon can use advanced
5213 * features to improve commutation and velocity measurement when using
5214 * a motor with hall sensors. This can improve peak efficiency by as
5215 * high as 2% and reduce noise in the measured velocity.
5216 *
5217 */
5219 /**
5220 * \brief Selects the motor and motor connections used with Talon.
5221 *
5222 * This setting determines what kind of motor and sensors are used
5223 * with the Talon. This also determines what signals are used on the
5224 * JST and Gadgeteer port.
5225 *
5226 * Motor drive will not function correctly if this setting does not
5227 * match the physical setup.
5228 *
5229 */
5231 /**
5232 * \brief If a brushed motor is selected with Motor Arrangement, this
5233 * config determines which of three leads to use.
5234 *
5235 */
5237
5238 /**
5239 * \brief Modifies this configuration's AdvancedHallSupport parameter and returns itself for
5240 * method-chaining and easier to use config API.
5241 *
5242 * Requires Phoenix Pro; Improves commutation and velocity measurement
5243 * for motors with hall sensors. Talon can use advanced features to
5244 * improve commutation and velocity measurement when using a motor
5245 * with hall sensors. This can improve peak efficiency by as high as
5246 * 2% and reduce noise in the measured velocity.
5247 *
5248 *
5249 * \param newAdvancedHallSupport Parameter to modify
5250 * \returns Itself
5251 */
5253 {
5254 AdvancedHallSupport = std::move(newAdvancedHallSupport);
5255 return *this;
5256 }
5257
5258 /**
5259 * \brief Modifies this configuration's MotorArrangement parameter and returns itself for
5260 * method-chaining and easier to use config API.
5261 *
5262 * Selects the motor and motor connections used with Talon.
5263 *
5264 * This setting determines what kind of motor and sensors are used
5265 * with the Talon. This also determines what signals are used on the
5266 * JST and Gadgeteer port.
5267 *
5268 * Motor drive will not function correctly if this setting does not
5269 * match the physical setup.
5270 *
5271 *
5272 * \param newMotorArrangement Parameter to modify
5273 * \returns Itself
5274 */
5276 {
5277 MotorArrangement = std::move(newMotorArrangement);
5278 return *this;
5279 }
5280
5281 /**
5282 * \brief Modifies this configuration's BrushedMotorWiring parameter and returns itself for
5283 * method-chaining and easier to use config API.
5284 *
5285 * If a brushed motor is selected with Motor Arrangement, this config
5286 * determines which of three leads to use.
5287 *
5288 *
5289 * \param newBrushedMotorWiring Parameter to modify
5290 * \returns Itself
5291 */
5293 {
5294 BrushedMotorWiring = std::move(newBrushedMotorWiring);
5295 return *this;
5296 }
5297
5298
5299
5300 std::string ToString() const override
5301 {
5302 std::stringstream ss;
5303 ss << "Config Group: Commutation" << std::endl;
5304 ss << " AdvancedHallSupport: " << AdvancedHallSupport << std::endl;
5305 ss << " MotorArrangement: " << MotorArrangement << std::endl;
5306 ss << " BrushedMotorWiring: " << BrushedMotorWiring << std::endl;
5307 return ss.str();
5308 }
5309
5310 std::string Serialize() const override
5311 {
5312 std::stringstream ss;
5313 char *ref;
5314 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_AdvancedHallSupport, AdvancedHallSupport.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5315 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_MotorType, MotorArrangement.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5316 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_BrushedMotorWiring, BrushedMotorWiring.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5317 return ss.str();
5318 }
5319
5320 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5321 {
5322 const char *string_c_str = to_deserialize.c_str();
5323 size_t string_length = to_deserialize.length();
5324 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_AdvancedHallSupport, string_c_str, string_length, &AdvancedHallSupport.value);
5325 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_MotorType, string_c_str, string_length, &MotorArrangement.value);
5326 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_BrushedMotorWiring, string_c_str, string_length, &BrushedMotorWiring.value);
5327 return 0;
5328 }
5329};
5330
5331
5332/**
5333 * \brief Configs related to CANdi digital I/O settings
5334 *
5335 * \details Contains float-state settings and when to assert the S1/S2
5336 * inputs.
5337 */
5339{
5340public:
5341 constexpr DigitalInputsConfigs() = default;
5342
5343 /**
5344 * \brief The floating state of the Signal 1 input (S1IN).
5345 *
5346 */
5348 /**
5349 * \brief The floating state of the Signal 2 input (S2IN).
5350 *
5351 */
5353 /**
5354 * \brief What value the Signal 1 input (S1IN) needs to be for the
5355 * CANdi to detect as Closed.
5356 *
5357 * \details Devices using the S1 input as a remote limit switch will
5358 * treat the switch as closed when the S1 input is this state.
5359 *
5360 */
5362 /**
5363 * \brief What value the Signal 2 input (S2IN) needs to be for the
5364 * CANdi to detect as Closed.
5365 *
5366 * \details Devices using the S2 input as a remote limit switch will
5367 * treat the switch as closed when the S2 input is this state.
5368 *
5369 */
5371
5372 /**
5373 * \brief Modifies this configuration's S1FloatState parameter and returns itself for
5374 * method-chaining and easier to use config API.
5375 *
5376 * The floating state of the Signal 1 input (S1IN).
5377 *
5378 *
5379 * \param newS1FloatState Parameter to modify
5380 * \returns Itself
5381 */
5383 {
5384 S1FloatState = std::move(newS1FloatState);
5385 return *this;
5386 }
5387
5388 /**
5389 * \brief Modifies this configuration's S2FloatState parameter and returns itself for
5390 * method-chaining and easier to use config API.
5391 *
5392 * The floating state of the Signal 2 input (S2IN).
5393 *
5394 *
5395 * \param newS2FloatState Parameter to modify
5396 * \returns Itself
5397 */
5399 {
5400 S2FloatState = std::move(newS2FloatState);
5401 return *this;
5402 }
5403
5404 /**
5405 * \brief Modifies this configuration's S1CloseState parameter and returns itself for
5406 * method-chaining and easier to use config API.
5407 *
5408 * What value the Signal 1 input (S1IN) needs to be for the CANdi to
5409 * detect as Closed.
5410 *
5411 * \details Devices using the S1 input as a remote limit switch will
5412 * treat the switch as closed when the S1 input is this state.
5413 *
5414 *
5415 * \param newS1CloseState Parameter to modify
5416 * \returns Itself
5417 */
5419 {
5420 S1CloseState = std::move(newS1CloseState);
5421 return *this;
5422 }
5423
5424 /**
5425 * \brief Modifies this configuration's S2CloseState parameter and returns itself for
5426 * method-chaining and easier to use config API.
5427 *
5428 * What value the Signal 2 input (S2IN) needs to be for the CANdi to
5429 * detect as Closed.
5430 *
5431 * \details Devices using the S2 input as a remote limit switch will
5432 * treat the switch as closed when the S2 input is this state.
5433 *
5434 *
5435 * \param newS2CloseState Parameter to modify
5436 * \returns Itself
5437 */
5439 {
5440 S2CloseState = std::move(newS2CloseState);
5441 return *this;
5442 }
5443
5444
5445
5446 std::string ToString() const override
5447 {
5448 std::stringstream ss;
5449 ss << "Config Group: DigitalInputs" << std::endl;
5450 ss << " S1FloatState: " << S1FloatState << std::endl;
5451 ss << " S2FloatState: " << S2FloatState << std::endl;
5452 ss << " S1CloseState: " << S1CloseState << std::endl;
5453 ss << " S2CloseState: " << S2CloseState << std::endl;
5454 return ss.str();
5455 }
5456
5457 std::string Serialize() const override
5458 {
5459 std::stringstream ss;
5460 char *ref;
5461 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S1FloatState, S1FloatState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5462 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S2FloatState, S2FloatState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5463 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_S1_CloseState, S1CloseState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5464 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_S2_CloseState, S2CloseState.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5465 return ss.str();
5466 }
5467
5468 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5469 {
5470 const char *string_c_str = to_deserialize.c_str();
5471 size_t string_length = to_deserialize.length();
5472 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S1FloatState, string_c_str, string_length, &S1FloatState.value);
5473 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::CANdi_S2FloatState, string_c_str, string_length, &S2FloatState.value);
5474 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_S1_CloseState, string_c_str, string_length, &S1CloseState.value);
5475 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_S2_CloseState, string_c_str, string_length, &S2CloseState.value);
5476 return 0;
5477 }
5478};
5479
5480
5481/**
5482 * \brief Configs related to CANdi's quadrature interface using both
5483 * the S1IN and S2IN inputs
5484 *
5485 * \details All the configs related to the quadrature interface for
5486 * CANdi, including encoder edges per revolution and sensor
5487 * direction.
5488 */
5490{
5491public:
5492 constexpr QuadratureConfigs() = default;
5493
5494 /**
5495 * \brief The number of quadrature edges in one rotation for the
5496 * quadrature sensor connected to the Talon data port.
5497 *
5498 * This is the total number of transitions from high-to-low or
5499 * low-to-high across both channels per rotation of the sensor. This
5500 * is also equivalent to the Counts Per Revolution when using 4x
5501 * decoding.
5502 *
5503 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
5504 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
5505 * 4096 edges per rotation.
5506 *
5507 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
5508 * RPM.
5509 *
5510 * - Minimum Value: 1
5511 * - Maximum Value: 1000000
5512 * - Default Value: 4096
5513 * - Units:
5514 */
5516 /**
5517 * \brief Direction of the quadrature sensor to determine positive
5518 * rotation. Invert this so that forward motion on the mechanism
5519 * results in an increase in quadrature position.
5520 *
5521 * - Default Value: False
5522 */
5523 bool SensorDirection = false;
5524
5525 /**
5526 * \brief Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for
5527 * method-chaining and easier to use config API.
5528 *
5529 * The number of quadrature edges in one rotation for the quadrature
5530 * sensor connected to the Talon data port.
5531 *
5532 * This is the total number of transitions from high-to-low or
5533 * low-to-high across both channels per rotation of the sensor. This
5534 * is also equivalent to the Counts Per Revolution when using 4x
5535 * decoding.
5536 *
5537 * For example, the SRX Mag Encoder has 4096 edges per rotation, and a
5538 * US Digital 1024 CPR (Cycles Per Revolution) quadrature encoder has
5539 * 4096 edges per rotation.
5540 *
5541 * \details On the Talon FXS, this can be at most 2,000,000,000 / Peak
5542 * RPM.
5543 *
5544 * - Minimum Value: 1
5545 * - Maximum Value: 1000000
5546 * - Default Value: 4096
5547 * - Units:
5548 *
5549 * \param newQuadratureEdgesPerRotation Parameter to modify
5550 * \returns Itself
5551 */
5552 constexpr QuadratureConfigs &WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
5553 {
5554 QuadratureEdgesPerRotation = std::move(newQuadratureEdgesPerRotation);
5555 return *this;
5556 }
5557
5558 /**
5559 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5560 * method-chaining and easier to use config API.
5561 *
5562 * Direction of the quadrature sensor to determine positive rotation.
5563 * Invert this so that forward motion on the mechanism results in an
5564 * increase in quadrature position.
5565 *
5566 * - Default Value: False
5567 *
5568 * \param newSensorDirection Parameter to modify
5569 * \returns Itself
5570 */
5571 constexpr QuadratureConfigs &WithSensorDirection(bool newSensorDirection)
5572 {
5573 SensorDirection = std::move(newSensorDirection);
5574 return *this;
5575 }
5576
5577
5578
5579 std::string ToString() const override
5580 {
5581 std::stringstream ss;
5582 ss << "Config Group: Quadrature" << std::endl;
5583 ss << " QuadratureEdgesPerRotation: " << QuadratureEdgesPerRotation << std::endl;
5584 ss << " SensorDirection: " << SensorDirection << std::endl;
5585 return ss.str();
5586 }
5587
5588 std::string Serialize() const override
5589 {
5590 std::stringstream ss;
5591 char *ref;
5592 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, QuadratureEdgesPerRotation, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5593 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_Quad_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5594 return ss.str();
5595 }
5596
5597 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5598 {
5599 const char *string_c_str = to_deserialize.c_str();
5600 size_t string_length = to_deserialize.length();
5601 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Config_QuadratureEdgesPerRotation, string_c_str, string_length, &QuadratureEdgesPerRotation);
5602 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_Quad_SensorDirection, string_c_str, string_length, &SensorDirection);
5603 return 0;
5604 }
5605};
5606
5607
5608/**
5609 * \brief Configs related to CANdi's PWM interface on the Signal 1
5610 * input (S1IN)
5611 *
5612 * \details All the configs related to the PWM interface for CANdi on
5613 * S1, including absolute sensor offset, absolute sensor
5614 * discontinuity point and sensor direction.
5615 */
5617{
5618public:
5619 constexpr PWM1Configs() = default;
5620
5621 /**
5622 * \brief The offset applied to the PWM sensor.
5623 *
5624 * This can be used to zero the sensor position in applications where
5625 * the sensor is 1:1 with the mechanism.
5626 *
5627 * - Minimum Value: -1
5628 * - Maximum Value: 1
5629 * - Default Value: 0.0
5630 * - Units: rotations
5631 */
5632 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
5633 /**
5634 * \brief The positive discontinuity point of the absolute sensor in
5635 * rotations. This determines the point at which the absolute sensor
5636 * wraps around, keeping the absolute position in the range [x-1, x).
5637 *
5638 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5639 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5640 * 0.5)
5641 * - Setting this to 0 makes the absolute position always negative
5642 * [-1, 0)
5643 *
5644 * Many rotational mechanisms such as arms have a region of motion
5645 * that is unreachable. This should be set to the center of that
5646 * region of motion, in non-negative rotations. This affects the
5647 * position of the device at bootup.
5648 *
5649 * \details For example, consider an arm which can travel from -0.2 to
5650 * 0.6 rotations with a little leeway, where 0 is horizontally
5651 * forward. Since -0.2 rotations has the same absolute position as 0.8
5652 * rotations, we can say that the arm typically does not travel in the
5653 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5654 * would be the center of that range, which is 0.7 rotations. This
5655 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5656 *
5657 * On a Talon motor controller, this is only supported when using the
5658 * PulseWidth sensor source.
5659 *
5660 * - Minimum Value: 0.0
5661 * - Maximum Value: 1.0
5662 * - Default Value: 0.5
5663 * - Units: rotations
5664 */
5665 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
5666 /**
5667 * \brief Direction of the PWM sensor to determine positive rotation.
5668 * Invert this so that forward motion on the mechanism results in an
5669 * increase in PWM position.
5670 *
5671 * - Default Value: False
5672 */
5673 bool SensorDirection = false;
5674
5675 /**
5676 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
5677 * method-chaining and easier to use config API.
5678 *
5679 * The offset applied to the PWM sensor.
5680 *
5681 * This can be used to zero the sensor position in applications where
5682 * the sensor is 1:1 with the mechanism.
5683 *
5684 * - Minimum Value: -1
5685 * - Maximum Value: 1
5686 * - Default Value: 0.0
5687 * - Units: rotations
5688 *
5689 * \param newAbsoluteSensorOffset Parameter to modify
5690 * \returns Itself
5691 */
5692 constexpr PWM1Configs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
5693 {
5694 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
5695 return *this;
5696 }
5697
5698 /**
5699 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
5700 * method-chaining and easier to use config API.
5701 *
5702 * The positive discontinuity point of the absolute sensor in
5703 * rotations. This determines the point at which the absolute sensor
5704 * wraps around, keeping the absolute position in the range [x-1, x).
5705 *
5706 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5707 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5708 * 0.5)
5709 * - Setting this to 0 makes the absolute position always negative
5710 * [-1, 0)
5711 *
5712 * Many rotational mechanisms such as arms have a region of motion
5713 * that is unreachable. This should be set to the center of that
5714 * region of motion, in non-negative rotations. This affects the
5715 * position of the device at bootup.
5716 *
5717 * \details For example, consider an arm which can travel from -0.2 to
5718 * 0.6 rotations with a little leeway, where 0 is horizontally
5719 * forward. Since -0.2 rotations has the same absolute position as 0.8
5720 * rotations, we can say that the arm typically does not travel in the
5721 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5722 * would be the center of that range, which is 0.7 rotations. This
5723 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5724 *
5725 * On a Talon motor controller, this is only supported when using the
5726 * PulseWidth sensor source.
5727 *
5728 * - Minimum Value: 0.0
5729 * - Maximum Value: 1.0
5730 * - Default Value: 0.5
5731 * - Units: rotations
5732 *
5733 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
5734 * \returns Itself
5735 */
5736 constexpr PWM1Configs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
5737 {
5738 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
5739 return *this;
5740 }
5741
5742 /**
5743 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5744 * method-chaining and easier to use config API.
5745 *
5746 * Direction of the PWM sensor to determine positive rotation. Invert
5747 * this so that forward motion on the mechanism results in an increase
5748 * in PWM position.
5749 *
5750 * - Default Value: False
5751 *
5752 * \param newSensorDirection Parameter to modify
5753 * \returns Itself
5754 */
5755 constexpr PWM1Configs &WithSensorDirection(bool newSensorDirection)
5756 {
5757 SensorDirection = std::move(newSensorDirection);
5758 return *this;
5759 }
5760
5761
5762
5763 std::string ToString() const override
5764 {
5765 std::stringstream ss;
5766 ss << "Config Group: PWM1" << std::endl;
5767 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
5768 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
5769 ss << " SensorDirection: " << SensorDirection << std::endl;
5770 return ss.str();
5771 }
5772
5773 std::string Serialize() const override
5774 {
5775 std::stringstream ss;
5776 char *ref;
5777 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5778 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5779 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM1_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5780 return ss.str();
5781 }
5782
5783 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5784 {
5785 const char *string_c_str = to_deserialize.c_str();
5786 size_t string_length = to_deserialize.length();
5787 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
5788 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
5789 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
5790 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
5791 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM1_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
5792 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
5793 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM1_SensorDirection, string_c_str, string_length, &SensorDirection);
5794 return 0;
5795 }
5796};
5797
5798
5799/**
5800 * \brief Configs related to CANdi's PWM interface on the Signal 2
5801 * input (S2IN)
5802 *
5803 * \details All the configs related to the PWM interface for CANdi on
5804 * S1, including absolute sensor offset, absolute sensor
5805 * discontinuity point and sensor direction.
5806 */
5808{
5809public:
5810 constexpr PWM2Configs() = default;
5811
5812 /**
5813 * \brief The offset applied to the PWM sensor.
5814 *
5815 * This can be used to zero the sensor position in applications where
5816 * the sensor is 1:1 with the mechanism.
5817 *
5818 * - Minimum Value: -1
5819 * - Maximum Value: 1
5820 * - Default Value: 0.0
5821 * - Units: rotations
5822 */
5823 units::angle::turn_t AbsoluteSensorOffset = 0.0_tr;
5824 /**
5825 * \brief The positive discontinuity point of the absolute sensor in
5826 * rotations. This determines the point at which the absolute sensor
5827 * wraps around, keeping the absolute position in the range [x-1, x).
5828 *
5829 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5830 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5831 * 0.5)
5832 * - Setting this to 0 makes the absolute position always negative
5833 * [-1, 0)
5834 *
5835 * Many rotational mechanisms such as arms have a region of motion
5836 * that is unreachable. This should be set to the center of that
5837 * region of motion, in non-negative rotations. This affects the
5838 * position of the device at bootup.
5839 *
5840 * \details For example, consider an arm which can travel from -0.2 to
5841 * 0.6 rotations with a little leeway, where 0 is horizontally
5842 * forward. Since -0.2 rotations has the same absolute position as 0.8
5843 * rotations, we can say that the arm typically does not travel in the
5844 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5845 * would be the center of that range, which is 0.7 rotations. This
5846 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5847 *
5848 * On a Talon motor controller, this is only supported when using the
5849 * PulseWidth sensor source.
5850 *
5851 * - Minimum Value: 0.0
5852 * - Maximum Value: 1.0
5853 * - Default Value: 0.5
5854 * - Units: rotations
5855 */
5856 units::angle::turn_t AbsoluteSensorDiscontinuityPoint = 0.5_tr;
5857 /**
5858 * \brief Direction of the PWM sensor to determine positive rotation.
5859 * Invert this so that forward motion on the mechanism results in an
5860 * increase in PWM position.
5861 *
5862 * - Default Value: False
5863 */
5864 bool SensorDirection = false;
5865
5866 /**
5867 * \brief Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for
5868 * method-chaining and easier to use config API.
5869 *
5870 * The offset applied to the PWM sensor.
5871 *
5872 * This can be used to zero the sensor position in applications where
5873 * the sensor is 1:1 with the mechanism.
5874 *
5875 * - Minimum Value: -1
5876 * - Maximum Value: 1
5877 * - Default Value: 0.0
5878 * - Units: rotations
5879 *
5880 * \param newAbsoluteSensorOffset Parameter to modify
5881 * \returns Itself
5882 */
5883 constexpr PWM2Configs &WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
5884 {
5885 AbsoluteSensorOffset = std::move(newAbsoluteSensorOffset);
5886 return *this;
5887 }
5888
5889 /**
5890 * \brief Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for
5891 * method-chaining and easier to use config API.
5892 *
5893 * The positive discontinuity point of the absolute sensor in
5894 * rotations. This determines the point at which the absolute sensor
5895 * wraps around, keeping the absolute position in the range [x-1, x).
5896 *
5897 * - Setting this to 1 makes the absolute position unsigned [0, 1)
5898 * - Setting this to 0.5 makes the absolute position signed [-0.5,
5899 * 0.5)
5900 * - Setting this to 0 makes the absolute position always negative
5901 * [-1, 0)
5902 *
5903 * Many rotational mechanisms such as arms have a region of motion
5904 * that is unreachable. This should be set to the center of that
5905 * region of motion, in non-negative rotations. This affects the
5906 * position of the device at bootup.
5907 *
5908 * \details For example, consider an arm which can travel from -0.2 to
5909 * 0.6 rotations with a little leeway, where 0 is horizontally
5910 * forward. Since -0.2 rotations has the same absolute position as 0.8
5911 * rotations, we can say that the arm typically does not travel in the
5912 * range (0.6, 0.8) rotations. As a result, the discontinuity point
5913 * would be the center of that range, which is 0.7 rotations. This
5914 * results in an absolute sensor range of [-0.3, 0.7) rotations.
5915 *
5916 * On a Talon motor controller, this is only supported when using the
5917 * PulseWidth sensor source.
5918 *
5919 * - Minimum Value: 0.0
5920 * - Maximum Value: 1.0
5921 * - Default Value: 0.5
5922 * - Units: rotations
5923 *
5924 * \param newAbsoluteSensorDiscontinuityPoint Parameter to modify
5925 * \returns Itself
5926 */
5927 constexpr PWM2Configs &WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
5928 {
5929 AbsoluteSensorDiscontinuityPoint = std::move(newAbsoluteSensorDiscontinuityPoint);
5930 return *this;
5931 }
5932
5933 /**
5934 * \brief Modifies this configuration's SensorDirection parameter and returns itself for
5935 * method-chaining and easier to use config API.
5936 *
5937 * Direction of the PWM sensor to determine positive rotation. Invert
5938 * this so that forward motion on the mechanism results in an increase
5939 * in PWM position.
5940 *
5941 * - Default Value: False
5942 *
5943 * \param newSensorDirection Parameter to modify
5944 * \returns Itself
5945 */
5946 constexpr PWM2Configs &WithSensorDirection(bool newSensorDirection)
5947 {
5948 SensorDirection = std::move(newSensorDirection);
5949 return *this;
5950 }
5951
5952
5953
5954 std::string ToString() const override
5955 {
5956 std::stringstream ss;
5957 ss << "Config Group: PWM2" << std::endl;
5958 ss << " AbsoluteSensorOffset: " << AbsoluteSensorOffset.to<double>() << " rotations" << std::endl;
5959 ss << " AbsoluteSensorDiscontinuityPoint: " << AbsoluteSensorDiscontinuityPoint.to<double>() << " rotations" << std::endl;
5960 ss << " SensorDirection: " << SensorDirection << std::endl;
5961 return ss.str();
5962 }
5963
5964 std::string Serialize() const override
5965 {
5966 std::stringstream ss;
5967 char *ref;
5968 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorOffset, AbsoluteSensorOffset.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5969 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorDiscontinuityPoint, AbsoluteSensorDiscontinuityPoint.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
5970 c_ctre_phoenix6_serialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM2_SensorDirection, SensorDirection, &ref); if (ref != nullptr) { ss << ref; free(ref); }
5971 return ss.str();
5972 }
5973
5974 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
5975 {
5976 const char *string_c_str = to_deserialize.c_str();
5977 size_t string_length = to_deserialize.length();
5978 double AbsoluteSensorOffsetVal = AbsoluteSensorOffset.to<double>();
5979 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorOffset, string_c_str, string_length, &AbsoluteSensorOffsetVal);
5980 AbsoluteSensorOffset = units::angle::turn_t{AbsoluteSensorOffsetVal};
5981 double AbsoluteSensorDiscontinuityPointVal = AbsoluteSensorDiscontinuityPoint.to<double>();
5982 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Config_PWM2_AbsoluteSensorDiscontinuityPoint, string_c_str, string_length, &AbsoluteSensorDiscontinuityPointVal);
5983 AbsoluteSensorDiscontinuityPoint = units::angle::turn_t{AbsoluteSensorDiscontinuityPointVal};
5984 c_ctre_phoenix6_deserialize_bool(ctre::phoenix6::spns::SpnValue::Config_PWM2_SensorDirection, string_c_str, string_length, &SensorDirection);
5985 return 0;
5986 }
5987};
5988
5989
5990/**
5991 * \brief Gains for the specified slot.
5992 *
5993 * \details If this slot is selected, these gains are used in closed
5994 * loop control requests.
5995 */
5997{
5998public:
5999 constexpr Slot0Configs() = default;
6000
6001 /**
6002 * \brief Proportional Gain.
6003 *
6004 * \details The units for this gain is dependent on the control mode.
6005 * Since this gain is multiplied by error in the input, the units
6006 * should be defined as units of output per unit of input error. For
6007 * example, when controlling velocity using a duty cycle closed loop,
6008 * the units for the proportional gain will be duty cycle per rps of
6009 * error, or 1/rps.
6010 *
6011 * - Minimum Value: 0
6012 * - Maximum Value: 3.4e+38
6013 * - Default Value: 0
6014 * - Units:
6015 */
6016 units::dimensionless::scalar_t kP = 0;
6017 /**
6018 * \brief Integral Gain.
6019 *
6020 * \details The units for this gain is dependent on the control mode.
6021 * Since this gain is multiplied by error in the input integrated over
6022 * time (in units of seconds), the units should be defined as units of
6023 * output per unit of integrated input error. For example, when
6024 * controlling velocity using a duty cycle closed loop, integrating
6025 * velocity over time results in rps * s = rotations. Therefore, the
6026 * units for the integral gain will be duty cycle per rotation of
6027 * accumulated error, or 1/rot.
6028 *
6029 * - Minimum Value: 0
6030 * - Maximum Value: 3.4e+38
6031 * - Default Value: 0
6032 * - Units:
6033 */
6034 units::dimensionless::scalar_t kI = 0;
6035 /**
6036 * \brief Derivative Gain.
6037 *
6038 * \details The units for this gain is dependent on the control mode.
6039 * Since this gain is multiplied by the derivative of error in the
6040 * input with respect to time (in units of seconds), the units should
6041 * be defined as units of output per unit of the differentiated input
6042 * error. For example, when controlling velocity using a duty cycle
6043 * closed loop, the derivative of velocity with respect to time is rot
6044 * per sec², which is acceleration. Therefore, the units for the
6045 * derivative gain will be duty cycle per unit of acceleration error,
6046 * or 1/(rot per sec²).
6047 *
6048 * - Minimum Value: 0
6049 * - Maximum Value: 3.4e+38
6050 * - Default Value: 0
6051 * - Units:
6052 */
6053 units::dimensionless::scalar_t kD = 0;
6054 /**
6055 * \brief Static Feedforward Gain.
6056 *
6057 * \details This is added to the closed loop output. The unit for this
6058 * constant is dependent on the control mode, typically fractional
6059 * duty cycle, voltage, or torque current.
6060 *
6061 * The sign is typically determined by reference velocity when using
6062 * position, velocity, and Motion Magic® closed loop modes. However,
6063 * when using position closed loop with zero velocity reference (no
6064 * motion profiling), the application can instead use the position
6065 * closed loop error by setting the Static Feedforward Sign
6066 * configuration parameter. When doing so, we recommend the minimal
6067 * amount of kS, otherwise the motor output may dither when closed
6068 * loop error is near zero.
6069 *
6070 * - Minimum Value: -512
6071 * - Maximum Value: 511
6072 * - Default Value: 0
6073 * - Units:
6074 */
6075 units::dimensionless::scalar_t kS = 0;
6076 /**
6077 * \brief Velocity Feedforward Gain.
6078 *
6079 * \details The units for this gain is dependent on the control mode.
6080 * Since this gain is multiplied by the requested velocity, the units
6081 * should be defined as units of output per unit of requested input
6082 * velocity. For example, when controlling velocity using a duty cycle
6083 * closed loop, the units for the velocity feedfoward gain will be
6084 * duty cycle per requested rps, or 1/rps.
6085 *
6086 * - Minimum Value: 0
6087 * - Maximum Value: 3.4e+38
6088 * - Default Value: 0
6089 * - Units:
6090 */
6091 units::dimensionless::scalar_t kV = 0;
6092 /**
6093 * \brief Acceleration Feedforward Gain.
6094 *
6095 * \details The units for this gain is dependent on the control mode.
6096 * Since this gain is multiplied by the requested acceleration, the
6097 * units should be defined as units of output per unit of requested
6098 * input acceleration. For example, when controlling velocity using a
6099 * duty cycle closed loop, the units for the acceleration feedfoward
6100 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6101 * sec²).
6102 *
6103 * - Minimum Value: 0
6104 * - Maximum Value: 3.4e+38
6105 * - Default Value: 0
6106 * - Units:
6107 */
6108 units::dimensionless::scalar_t kA = 0;
6109 /**
6110 * \brief Gravity Feedforward/Feedback Gain.
6111 *
6112 * \details This is added to the closed loop output. The sign is
6113 * determined by GravityType. The unit for this constant is dependent
6114 * on the control mode, typically fractional duty cycle, voltage, or
6115 * torque current.
6116 *
6117 * - Minimum Value: -512
6118 * - Maximum Value: 511
6119 * - Default Value: 0
6120 * - Units:
6121 */
6122 units::dimensionless::scalar_t kG = 0;
6123 /**
6124 * \brief Gravity Feedforward/Feedback Type.
6125 *
6126 * This determines the type of the gravity feedforward/feedback.
6127 *
6128 * Choose Elevator_Static for systems where the gravity feedforward is
6129 * constant, such as an elevator. The gravity feedforward output will
6130 * always have the same sign.
6131 *
6132 * Choose Arm_Cosine for systems where the gravity feedback is
6133 * dependent on the angular position of the mechanism, such as an arm.
6134 * The gravity feedback output will vary depending on the mechanism
6135 * angular position. Note that the sensor offset and ratios must be
6136 * configured so that the sensor reports a position of 0 when the
6137 * mechanism is horizonal (parallel to the ground), and the reported
6138 * sensor position is 1:1 with the mechanism.
6139 *
6140 */
6142 /**
6143 * \brief Static Feedforward Sign during position closed loop.
6144 *
6145 * This determines the sign of the applied kS during position
6146 * closed-loop modes. The default behavior uses the velocity reference
6147 * sign. This works well with velocity closed loop, Motion Magic®
6148 * controls, and position closed loop when velocity reference is
6149 * specified (motion profiling).
6150 *
6151 * However, when using position closed loop with zero velocity
6152 * reference (no motion profiling), the application may want to apply
6153 * static feedforward based on the sign of closed loop error instead.
6154 * When doing so, we recommend using the minimal amount of kS,
6155 * otherwise the motor output may dither when closed loop error is
6156 * near zero.
6157 *
6158 */
6160
6161 /**
6162 * \brief Modifies this configuration's kP parameter and returns itself for
6163 * method-chaining and easier to use config API.
6164 *
6165 * Proportional Gain.
6166 *
6167 * \details The units for this gain is dependent on the control mode.
6168 * Since this gain is multiplied by error in the input, the units
6169 * should be defined as units of output per unit of input error. For
6170 * example, when controlling velocity using a duty cycle closed loop,
6171 * the units for the proportional gain will be duty cycle per rps of
6172 * error, or 1/rps.
6173 *
6174 * - Minimum Value: 0
6175 * - Maximum Value: 3.4e+38
6176 * - Default Value: 0
6177 * - Units:
6178 *
6179 * \param newKP Parameter to modify
6180 * \returns Itself
6181 */
6182 constexpr Slot0Configs &WithKP(units::dimensionless::scalar_t newKP)
6183 {
6184 kP = std::move(newKP);
6185 return *this;
6186 }
6187
6188 /**
6189 * \brief Modifies this configuration's kI parameter and returns itself for
6190 * method-chaining and easier to use config API.
6191 *
6192 * Integral Gain.
6193 *
6194 * \details The units for this gain is dependent on the control mode.
6195 * Since this gain is multiplied by error in the input integrated over
6196 * time (in units of seconds), the units should be defined as units of
6197 * output per unit of integrated input error. For example, when
6198 * controlling velocity using a duty cycle closed loop, integrating
6199 * velocity over time results in rps * s = rotations. Therefore, the
6200 * units for the integral gain will be duty cycle per rotation of
6201 * accumulated error, or 1/rot.
6202 *
6203 * - Minimum Value: 0
6204 * - Maximum Value: 3.4e+38
6205 * - Default Value: 0
6206 * - Units:
6207 *
6208 * \param newKI Parameter to modify
6209 * \returns Itself
6210 */
6211 constexpr Slot0Configs &WithKI(units::dimensionless::scalar_t newKI)
6212 {
6213 kI = std::move(newKI);
6214 return *this;
6215 }
6216
6217 /**
6218 * \brief Modifies this configuration's kD parameter and returns itself for
6219 * method-chaining and easier to use config API.
6220 *
6221 * Derivative Gain.
6222 *
6223 * \details The units for this gain is dependent on the control mode.
6224 * Since this gain is multiplied by the derivative of error in the
6225 * input with respect to time (in units of seconds), the units should
6226 * be defined as units of output per unit of the differentiated input
6227 * error. For example, when controlling velocity using a duty cycle
6228 * closed loop, the derivative of velocity with respect to time is rot
6229 * per sec², which is acceleration. Therefore, the units for the
6230 * derivative gain will be duty cycle per unit of acceleration error,
6231 * or 1/(rot per sec²).
6232 *
6233 * - Minimum Value: 0
6234 * - Maximum Value: 3.4e+38
6235 * - Default Value: 0
6236 * - Units:
6237 *
6238 * \param newKD Parameter to modify
6239 * \returns Itself
6240 */
6241 constexpr Slot0Configs &WithKD(units::dimensionless::scalar_t newKD)
6242 {
6243 kD = std::move(newKD);
6244 return *this;
6245 }
6246
6247 /**
6248 * \brief Modifies this configuration's kS parameter and returns itself for
6249 * method-chaining and easier to use config API.
6250 *
6251 * Static Feedforward Gain.
6252 *
6253 * \details This is added to the closed loop output. The unit for this
6254 * constant is dependent on the control mode, typically fractional
6255 * duty cycle, voltage, or torque current.
6256 *
6257 * The sign is typically determined by reference velocity when using
6258 * position, velocity, and Motion Magic® closed loop modes. However,
6259 * when using position closed loop with zero velocity reference (no
6260 * motion profiling), the application can instead use the position
6261 * closed loop error by setting the Static Feedforward Sign
6262 * configuration parameter. When doing so, we recommend the minimal
6263 * amount of kS, otherwise the motor output may dither when closed
6264 * loop error is near zero.
6265 *
6266 * - Minimum Value: -512
6267 * - Maximum Value: 511
6268 * - Default Value: 0
6269 * - Units:
6270 *
6271 * \param newKS Parameter to modify
6272 * \returns Itself
6273 */
6274 constexpr Slot0Configs &WithKS(units::dimensionless::scalar_t newKS)
6275 {
6276 kS = std::move(newKS);
6277 return *this;
6278 }
6279
6280 /**
6281 * \brief Modifies this configuration's kV parameter and returns itself for
6282 * method-chaining and easier to use config API.
6283 *
6284 * Velocity Feedforward Gain.
6285 *
6286 * \details The units for this gain is dependent on the control mode.
6287 * Since this gain is multiplied by the requested velocity, the units
6288 * should be defined as units of output per unit of requested input
6289 * velocity. For example, when controlling velocity using a duty cycle
6290 * closed loop, the units for the velocity feedfoward gain will be
6291 * duty cycle per requested rps, or 1/rps.
6292 *
6293 * - Minimum Value: 0
6294 * - Maximum Value: 3.4e+38
6295 * - Default Value: 0
6296 * - Units:
6297 *
6298 * \param newKV Parameter to modify
6299 * \returns Itself
6300 */
6301 constexpr Slot0Configs &WithKV(units::dimensionless::scalar_t newKV)
6302 {
6303 kV = std::move(newKV);
6304 return *this;
6305 }
6306
6307 /**
6308 * \brief Modifies this configuration's kA parameter and returns itself for
6309 * method-chaining and easier to use config API.
6310 *
6311 * Acceleration Feedforward Gain.
6312 *
6313 * \details The units for this gain is dependent on the control mode.
6314 * Since this gain is multiplied by the requested acceleration, the
6315 * units should be defined as units of output per unit of requested
6316 * input acceleration. For example, when controlling velocity using a
6317 * duty cycle closed loop, the units for the acceleration feedfoward
6318 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6319 * sec²).
6320 *
6321 * - Minimum Value: 0
6322 * - Maximum Value: 3.4e+38
6323 * - Default Value: 0
6324 * - Units:
6325 *
6326 * \param newKA Parameter to modify
6327 * \returns Itself
6328 */
6329 constexpr Slot0Configs &WithKA(units::dimensionless::scalar_t newKA)
6330 {
6331 kA = std::move(newKA);
6332 return *this;
6333 }
6334
6335 /**
6336 * \brief Modifies this configuration's kG parameter and returns itself for
6337 * method-chaining and easier to use config API.
6338 *
6339 * Gravity Feedforward/Feedback Gain.
6340 *
6341 * \details This is added to the closed loop output. The sign is
6342 * determined by GravityType. The unit for this constant is dependent
6343 * on the control mode, typically fractional duty cycle, voltage, or
6344 * torque current.
6345 *
6346 * - Minimum Value: -512
6347 * - Maximum Value: 511
6348 * - Default Value: 0
6349 * - Units:
6350 *
6351 * \param newKG Parameter to modify
6352 * \returns Itself
6353 */
6354 constexpr Slot0Configs &WithKG(units::dimensionless::scalar_t newKG)
6355 {
6356 kG = std::move(newKG);
6357 return *this;
6358 }
6359
6360 /**
6361 * \brief Modifies this configuration's GravityType parameter and returns itself for
6362 * method-chaining and easier to use config API.
6363 *
6364 * Gravity Feedforward/Feedback Type.
6365 *
6366 * This determines the type of the gravity feedforward/feedback.
6367 *
6368 * Choose Elevator_Static for systems where the gravity feedforward is
6369 * constant, such as an elevator. The gravity feedforward output will
6370 * always have the same sign.
6371 *
6372 * Choose Arm_Cosine for systems where the gravity feedback is
6373 * dependent on the angular position of the mechanism, such as an arm.
6374 * The gravity feedback output will vary depending on the mechanism
6375 * angular position. Note that the sensor offset and ratios must be
6376 * configured so that the sensor reports a position of 0 when the
6377 * mechanism is horizonal (parallel to the ground), and the reported
6378 * sensor position is 1:1 with the mechanism.
6379 *
6380 *
6381 * \param newGravityType Parameter to modify
6382 * \returns Itself
6383 */
6385 {
6386 GravityType = std::move(newGravityType);
6387 return *this;
6388 }
6389
6390 /**
6391 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
6392 * method-chaining and easier to use config API.
6393 *
6394 * Static Feedforward Sign during position closed loop.
6395 *
6396 * This determines the sign of the applied kS during position
6397 * closed-loop modes. The default behavior uses the velocity reference
6398 * sign. This works well with velocity closed loop, Motion Magic®
6399 * controls, and position closed loop when velocity reference is
6400 * specified (motion profiling).
6401 *
6402 * However, when using position closed loop with zero velocity
6403 * reference (no motion profiling), the application may want to apply
6404 * static feedforward based on the sign of closed loop error instead.
6405 * When doing so, we recommend using the minimal amount of kS,
6406 * otherwise the motor output may dither when closed loop error is
6407 * near zero.
6408 *
6409 *
6410 * \param newStaticFeedforwardSign Parameter to modify
6411 * \returns Itself
6412 */
6414 {
6415 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
6416 return *this;
6417 }
6418
6419 static Slot0Configs From(const SlotConfigs &value);
6420
6421 std::string ToString() const override
6422 {
6423 std::stringstream ss;
6424 ss << "Config Group: Slot0" << std::endl;
6425 ss << " kP: " << kP.to<double>() << std::endl;
6426 ss << " kI: " << kI.to<double>() << std::endl;
6427 ss << " kD: " << kD.to<double>() << std::endl;
6428 ss << " kS: " << kS.to<double>() << std::endl;
6429 ss << " kV: " << kV.to<double>() << std::endl;
6430 ss << " kA: " << kA.to<double>() << std::endl;
6431 ss << " kG: " << kG.to<double>() << std::endl;
6432 ss << " GravityType: " << GravityType << std::endl;
6433 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
6434 return ss.str();
6435 }
6436
6437 std::string Serialize() const override
6438 {
6439 std::stringstream ss;
6440 char *ref;
6441 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6442 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6443 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6444 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6445 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6446 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6447 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6448 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6449 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6450 return ss.str();
6451 }
6452
6453 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
6454 {
6455 const char *string_c_str = to_deserialize.c_str();
6456 size_t string_length = to_deserialize.length();
6457 double kPVal = kP.to<double>();
6458 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kP, string_c_str, string_length, &kPVal);
6459 kP = units::dimensionless::scalar_t{kPVal};
6460 double kIVal = kI.to<double>();
6461 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kI, string_c_str, string_length, &kIVal);
6462 kI = units::dimensionless::scalar_t{kIVal};
6463 double kDVal = kD.to<double>();
6464 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kD, string_c_str, string_length, &kDVal);
6465 kD = units::dimensionless::scalar_t{kDVal};
6466 double kSVal = kS.to<double>();
6467 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kS, string_c_str, string_length, &kSVal);
6468 kS = units::dimensionless::scalar_t{kSVal};
6469 double kVVal = kV.to<double>();
6470 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kV, string_c_str, string_length, &kVVal);
6471 kV = units::dimensionless::scalar_t{kVVal};
6472 double kAVal = kA.to<double>();
6473 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kA, string_c_str, string_length, &kAVal);
6474 kA = units::dimensionless::scalar_t{kAVal};
6475 double kGVal = kG.to<double>();
6476 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot0_kG, string_c_str, string_length, &kGVal);
6477 kG = units::dimensionless::scalar_t{kGVal};
6478 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kG_Type, string_c_str, string_length, &GravityType.value);
6479 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
6480 return 0;
6481 }
6482};
6483
6484
6485/**
6486 * \brief Gains for the specified slot.
6487 *
6488 * \details If this slot is selected, these gains are used in closed
6489 * loop control requests.
6490 */
6492{
6493public:
6494 constexpr Slot1Configs() = default;
6495
6496 /**
6497 * \brief Proportional Gain.
6498 *
6499 * \details The units for this gain is dependent on the control mode.
6500 * Since this gain is multiplied by error in the input, the units
6501 * should be defined as units of output per unit of input error. For
6502 * example, when controlling velocity using a duty cycle closed loop,
6503 * the units for the proportional gain will be duty cycle per rps, or
6504 * 1/rps.
6505 *
6506 * - Minimum Value: 0
6507 * - Maximum Value: 3.4e+38
6508 * - Default Value: 0
6509 * - Units:
6510 */
6511 units::dimensionless::scalar_t kP = 0;
6512 /**
6513 * \brief Integral Gain.
6514 *
6515 * \details The units for this gain is dependent on the control mode.
6516 * Since this gain is multiplied by error in the input integrated over
6517 * time (in units of seconds), the units should be defined as units of
6518 * output per unit of integrated input error. For example, when
6519 * controlling velocity using a duty cycle closed loop, integrating
6520 * velocity over time results in rps * s = rotations. Therefore, the
6521 * units for the integral gain will be duty cycle per rotation of
6522 * accumulated error, or 1/rot.
6523 *
6524 * - Minimum Value: 0
6525 * - Maximum Value: 3.4e+38
6526 * - Default Value: 0
6527 * - Units:
6528 */
6529 units::dimensionless::scalar_t kI = 0;
6530 /**
6531 * \brief Derivative Gain.
6532 *
6533 * \details The units for this gain is dependent on the control mode.
6534 * Since this gain is multiplied by the derivative of error in the
6535 * input with respect to time (in units of seconds), the units should
6536 * be defined as units of output per unit of the differentiated input
6537 * error. For example, when controlling velocity using a duty cycle
6538 * closed loop, the derivative of velocity with respect to time is rot
6539 * per sec², which is acceleration. Therefore, the units for the
6540 * derivative gain will be duty cycle per unit of acceleration error,
6541 * or 1/(rot per sec²).
6542 *
6543 * - Minimum Value: 0
6544 * - Maximum Value: 3.4e+38
6545 * - Default Value: 0
6546 * - Units:
6547 */
6548 units::dimensionless::scalar_t kD = 0;
6549 /**
6550 * \brief Static Feedforward Gain.
6551 *
6552 * \details This is added to the closed loop output. The unit for this
6553 * constant is dependent on the control mode, typically fractional
6554 * duty cycle, voltage, or torque current.
6555 *
6556 * The sign is typically determined by reference velocity when using
6557 * position, velocity, and Motion Magic® closed loop modes. However,
6558 * when using position closed loop with zero velocity reference (no
6559 * motion profiling), the application can instead use the position
6560 * closed loop error by setting the Static Feedforward Sign
6561 * configuration parameter. When doing so, we recommend the minimal
6562 * amount of kS, otherwise the motor output may dither when closed
6563 * loop error is near zero.
6564 *
6565 * - Minimum Value: -512
6566 * - Maximum Value: 511
6567 * - Default Value: 0
6568 * - Units:
6569 */
6570 units::dimensionless::scalar_t kS = 0;
6571 /**
6572 * \brief Velocity Feedforward Gain.
6573 *
6574 * \details The units for this gain is dependent on the control mode.
6575 * Since this gain is multiplied by the requested velocity, the units
6576 * should be defined as units of output per unit of requested input
6577 * velocity. For example, when controlling velocity using a duty cycle
6578 * closed loop, the units for the velocity feedfoward gain will be
6579 * duty cycle per requested rps, or 1/rps.
6580 *
6581 * - Minimum Value: 0
6582 * - Maximum Value: 3.4e+38
6583 * - Default Value: 0
6584 * - Units:
6585 */
6586 units::dimensionless::scalar_t kV = 0;
6587 /**
6588 * \brief Acceleration Feedforward Gain.
6589 *
6590 * \details The units for this gain is dependent on the control mode.
6591 * Since this gain is multiplied by the requested acceleration, the
6592 * units should be defined as units of output per unit of requested
6593 * input acceleration. For example, when controlling velocity using a
6594 * duty cycle closed loop, the units for the acceleration feedfoward
6595 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6596 * sec²).
6597 *
6598 * - Minimum Value: 0
6599 * - Maximum Value: 3.4e+38
6600 * - Default Value: 0
6601 * - Units:
6602 */
6603 units::dimensionless::scalar_t kA = 0;
6604 /**
6605 * \brief Gravity Feedforward/Feedback Gain.
6606 *
6607 * \details This is added to the closed loop output. The sign is
6608 * determined by GravityType. The unit for this constant is dependent
6609 * on the control mode, typically fractional duty cycle, voltage, or
6610 * torque current.
6611 *
6612 * - Minimum Value: -512
6613 * - Maximum Value: 511
6614 * - Default Value: 0
6615 * - Units:
6616 */
6617 units::dimensionless::scalar_t kG = 0;
6618 /**
6619 * \brief Gravity Feedforward/Feedback Type.
6620 *
6621 * This determines the type of the gravity feedforward/feedback.
6622 *
6623 * Choose Elevator_Static for systems where the gravity feedforward is
6624 * constant, such as an elevator. The gravity feedforward output will
6625 * always be positive.
6626 *
6627 * Choose Arm_Cosine for systems where the gravity feedback is
6628 * dependent on the angular position of the mechanism, such as an arm.
6629 * The gravity feedback output will vary depending on the mechanism
6630 * angular position. Note that the sensor offset and ratios must be
6631 * configured so that the sensor position is 0 when the mechanism is
6632 * horizonal, and one rotation of the mechanism corresponds to one
6633 * rotation of the sensor position.
6634 *
6635 */
6637 /**
6638 * \brief Static Feedforward Sign during position closed loop.
6639 *
6640 * This determines the sign of the applied kS during position
6641 * closed-loop modes. The default behavior uses the velocity reference
6642 * sign. This works well with velocity closed loop, Motion Magic®
6643 * controls, and position closed loop when velocity reference is
6644 * specified (motion profiling).
6645 *
6646 * However, when using position closed loop with zero velocity
6647 * reference (no motion profiling), the application may want to apply
6648 * static feedforward based on the closed loop error sign instead.
6649 * When doing so, we recommend using the minimal amount of kS,
6650 * otherwise the motor output may dither when closed loop error is
6651 * near zero.
6652 *
6653 */
6655
6656 /**
6657 * \brief Modifies this configuration's kP parameter and returns itself for
6658 * method-chaining and easier to use config API.
6659 *
6660 * Proportional Gain.
6661 *
6662 * \details The units for this gain is dependent on the control mode.
6663 * Since this gain is multiplied by error in the input, the units
6664 * should be defined as units of output per unit of input error. For
6665 * example, when controlling velocity using a duty cycle closed loop,
6666 * the units for the proportional gain will be duty cycle per rps, or
6667 * 1/rps.
6668 *
6669 * - Minimum Value: 0
6670 * - Maximum Value: 3.4e+38
6671 * - Default Value: 0
6672 * - Units:
6673 *
6674 * \param newKP Parameter to modify
6675 * \returns Itself
6676 */
6677 constexpr Slot1Configs &WithKP(units::dimensionless::scalar_t newKP)
6678 {
6679 kP = std::move(newKP);
6680 return *this;
6681 }
6682
6683 /**
6684 * \brief Modifies this configuration's kI parameter and returns itself for
6685 * method-chaining and easier to use config API.
6686 *
6687 * Integral Gain.
6688 *
6689 * \details The units for this gain is dependent on the control mode.
6690 * Since this gain is multiplied by error in the input integrated over
6691 * time (in units of seconds), the units should be defined as units of
6692 * output per unit of integrated input error. For example, when
6693 * controlling velocity using a duty cycle closed loop, integrating
6694 * velocity over time results in rps * s = rotations. Therefore, the
6695 * units for the integral gain will be duty cycle per rotation of
6696 * accumulated error, or 1/rot.
6697 *
6698 * - Minimum Value: 0
6699 * - Maximum Value: 3.4e+38
6700 * - Default Value: 0
6701 * - Units:
6702 *
6703 * \param newKI Parameter to modify
6704 * \returns Itself
6705 */
6706 constexpr Slot1Configs &WithKI(units::dimensionless::scalar_t newKI)
6707 {
6708 kI = std::move(newKI);
6709 return *this;
6710 }
6711
6712 /**
6713 * \brief Modifies this configuration's kD parameter and returns itself for
6714 * method-chaining and easier to use config API.
6715 *
6716 * Derivative Gain.
6717 *
6718 * \details The units for this gain is dependent on the control mode.
6719 * Since this gain is multiplied by the derivative of error in the
6720 * input with respect to time (in units of seconds), the units should
6721 * be defined as units of output per unit of the differentiated input
6722 * error. For example, when controlling velocity using a duty cycle
6723 * closed loop, the derivative of velocity with respect to time is rot
6724 * per sec², which is acceleration. Therefore, the units for the
6725 * derivative gain will be duty cycle per unit of acceleration error,
6726 * or 1/(rot per sec²).
6727 *
6728 * - Minimum Value: 0
6729 * - Maximum Value: 3.4e+38
6730 * - Default Value: 0
6731 * - Units:
6732 *
6733 * \param newKD Parameter to modify
6734 * \returns Itself
6735 */
6736 constexpr Slot1Configs &WithKD(units::dimensionless::scalar_t newKD)
6737 {
6738 kD = std::move(newKD);
6739 return *this;
6740 }
6741
6742 /**
6743 * \brief Modifies this configuration's kS parameter and returns itself for
6744 * method-chaining and easier to use config API.
6745 *
6746 * Static Feedforward Gain.
6747 *
6748 * \details This is added to the closed loop output. The unit for this
6749 * constant is dependent on the control mode, typically fractional
6750 * duty cycle, voltage, or torque current.
6751 *
6752 * The sign is typically determined by reference velocity when using
6753 * position, velocity, and Motion Magic® closed loop modes. However,
6754 * when using position closed loop with zero velocity reference (no
6755 * motion profiling), the application can instead use the position
6756 * closed loop error by setting the Static Feedforward Sign
6757 * configuration parameter. When doing so, we recommend the minimal
6758 * amount of kS, otherwise the motor output may dither when closed
6759 * loop error is near zero.
6760 *
6761 * - Minimum Value: -512
6762 * - Maximum Value: 511
6763 * - Default Value: 0
6764 * - Units:
6765 *
6766 * \param newKS Parameter to modify
6767 * \returns Itself
6768 */
6769 constexpr Slot1Configs &WithKS(units::dimensionless::scalar_t newKS)
6770 {
6771 kS = std::move(newKS);
6772 return *this;
6773 }
6774
6775 /**
6776 * \brief Modifies this configuration's kV parameter and returns itself for
6777 * method-chaining and easier to use config API.
6778 *
6779 * Velocity Feedforward Gain.
6780 *
6781 * \details The units for this gain is dependent on the control mode.
6782 * Since this gain is multiplied by the requested velocity, the units
6783 * should be defined as units of output per unit of requested input
6784 * velocity. For example, when controlling velocity using a duty cycle
6785 * closed loop, the units for the velocity feedfoward gain will be
6786 * duty cycle per requested rps, or 1/rps.
6787 *
6788 * - Minimum Value: 0
6789 * - Maximum Value: 3.4e+38
6790 * - Default Value: 0
6791 * - Units:
6792 *
6793 * \param newKV Parameter to modify
6794 * \returns Itself
6795 */
6796 constexpr Slot1Configs &WithKV(units::dimensionless::scalar_t newKV)
6797 {
6798 kV = std::move(newKV);
6799 return *this;
6800 }
6801
6802 /**
6803 * \brief Modifies this configuration's kA parameter and returns itself for
6804 * method-chaining and easier to use config API.
6805 *
6806 * Acceleration Feedforward Gain.
6807 *
6808 * \details The units for this gain is dependent on the control mode.
6809 * Since this gain is multiplied by the requested acceleration, the
6810 * units should be defined as units of output per unit of requested
6811 * input acceleration. For example, when controlling velocity using a
6812 * duty cycle closed loop, the units for the acceleration feedfoward
6813 * gain will be duty cycle per requested rot per sec², or 1/(rot per
6814 * sec²).
6815 *
6816 * - Minimum Value: 0
6817 * - Maximum Value: 3.4e+38
6818 * - Default Value: 0
6819 * - Units:
6820 *
6821 * \param newKA Parameter to modify
6822 * \returns Itself
6823 */
6824 constexpr Slot1Configs &WithKA(units::dimensionless::scalar_t newKA)
6825 {
6826 kA = std::move(newKA);
6827 return *this;
6828 }
6829
6830 /**
6831 * \brief Modifies this configuration's kG parameter and returns itself for
6832 * method-chaining and easier to use config API.
6833 *
6834 * Gravity Feedforward/Feedback Gain.
6835 *
6836 * \details This is added to the closed loop output. The sign is
6837 * determined by GravityType. The unit for this constant is dependent
6838 * on the control mode, typically fractional duty cycle, voltage, or
6839 * torque current.
6840 *
6841 * - Minimum Value: -512
6842 * - Maximum Value: 511
6843 * - Default Value: 0
6844 * - Units:
6845 *
6846 * \param newKG Parameter to modify
6847 * \returns Itself
6848 */
6849 constexpr Slot1Configs &WithKG(units::dimensionless::scalar_t newKG)
6850 {
6851 kG = std::move(newKG);
6852 return *this;
6853 }
6854
6855 /**
6856 * \brief Modifies this configuration's GravityType parameter and returns itself for
6857 * method-chaining and easier to use config API.
6858 *
6859 * Gravity Feedforward/Feedback Type.
6860 *
6861 * This determines the type of the gravity feedforward/feedback.
6862 *
6863 * Choose Elevator_Static for systems where the gravity feedforward is
6864 * constant, such as an elevator. The gravity feedforward output will
6865 * always be positive.
6866 *
6867 * Choose Arm_Cosine for systems where the gravity feedback is
6868 * dependent on the angular position of the mechanism, such as an arm.
6869 * The gravity feedback output will vary depending on the mechanism
6870 * angular position. Note that the sensor offset and ratios must be
6871 * configured so that the sensor position is 0 when the mechanism is
6872 * horizonal, and one rotation of the mechanism corresponds to one
6873 * rotation of the sensor position.
6874 *
6875 *
6876 * \param newGravityType Parameter to modify
6877 * \returns Itself
6878 */
6880 {
6881 GravityType = std::move(newGravityType);
6882 return *this;
6883 }
6884
6885 /**
6886 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
6887 * method-chaining and easier to use config API.
6888 *
6889 * Static Feedforward Sign during position closed loop.
6890 *
6891 * This determines the sign of the applied kS during position
6892 * closed-loop modes. The default behavior uses the velocity reference
6893 * sign. This works well with velocity closed loop, Motion Magic®
6894 * controls, and position closed loop when velocity reference is
6895 * specified (motion profiling).
6896 *
6897 * However, when using position closed loop with zero velocity
6898 * reference (no motion profiling), the application may want to apply
6899 * static feedforward based on the closed loop error sign instead.
6900 * When doing so, we recommend using the minimal amount of kS,
6901 * otherwise the motor output may dither when closed loop error is
6902 * near zero.
6903 *
6904 *
6905 * \param newStaticFeedforwardSign Parameter to modify
6906 * \returns Itself
6907 */
6909 {
6910 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
6911 return *this;
6912 }
6913
6914 static Slot1Configs From(const SlotConfigs &value);
6915
6916 std::string ToString() const override
6917 {
6918 std::stringstream ss;
6919 ss << "Config Group: Slot1" << std::endl;
6920 ss << " kP: " << kP.to<double>() << std::endl;
6921 ss << " kI: " << kI.to<double>() << std::endl;
6922 ss << " kD: " << kD.to<double>() << std::endl;
6923 ss << " kS: " << kS.to<double>() << std::endl;
6924 ss << " kV: " << kV.to<double>() << std::endl;
6925 ss << " kA: " << kA.to<double>() << std::endl;
6926 ss << " kG: " << kG.to<double>() << std::endl;
6927 ss << " GravityType: " << GravityType << std::endl;
6928 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
6929 return ss.str();
6930 }
6931
6932 std::string Serialize() const override
6933 {
6934 std::stringstream ss;
6935 char *ref;
6936 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6937 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6938 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6939 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6940 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6941 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6942 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
6943 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6944 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
6945 return ss.str();
6946 }
6947
6948 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
6949 {
6950 const char *string_c_str = to_deserialize.c_str();
6951 size_t string_length = to_deserialize.length();
6952 double kPVal = kP.to<double>();
6953 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kP, string_c_str, string_length, &kPVal);
6954 kP = units::dimensionless::scalar_t{kPVal};
6955 double kIVal = kI.to<double>();
6956 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kI, string_c_str, string_length, &kIVal);
6957 kI = units::dimensionless::scalar_t{kIVal};
6958 double kDVal = kD.to<double>();
6959 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kD, string_c_str, string_length, &kDVal);
6960 kD = units::dimensionless::scalar_t{kDVal};
6961 double kSVal = kS.to<double>();
6962 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kS, string_c_str, string_length, &kSVal);
6963 kS = units::dimensionless::scalar_t{kSVal};
6964 double kVVal = kV.to<double>();
6965 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kV, string_c_str, string_length, &kVVal);
6966 kV = units::dimensionless::scalar_t{kVVal};
6967 double kAVal = kA.to<double>();
6968 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kA, string_c_str, string_length, &kAVal);
6969 kA = units::dimensionless::scalar_t{kAVal};
6970 double kGVal = kG.to<double>();
6971 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot1_kG, string_c_str, string_length, &kGVal);
6972 kG = units::dimensionless::scalar_t{kGVal};
6973 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kG_Type, string_c_str, string_length, &GravityType.value);
6974 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
6975 return 0;
6976 }
6977};
6978
6979
6980/**
6981 * \brief Gains for the specified slot.
6982 *
6983 * \details If this slot is selected, these gains are used in closed
6984 * loop control requests.
6985 */
6987{
6988public:
6989 constexpr Slot2Configs() = default;
6990
6991 /**
6992 * \brief Proportional Gain.
6993 *
6994 * \details The units for this gain is dependent on the control mode.
6995 * Since this gain is multiplied by error in the input, the units
6996 * should be defined as units of output per unit of input error. For
6997 * example, when controlling velocity using a duty cycle closed loop,
6998 * the units for the proportional gain will be duty cycle per rps, or
6999 * 1/rps.
7000 *
7001 * - Minimum Value: 0
7002 * - Maximum Value: 3.4e+38
7003 * - Default Value: 0
7004 * - Units:
7005 */
7006 units::dimensionless::scalar_t kP = 0;
7007 /**
7008 * \brief Integral Gain.
7009 *
7010 * \details The units for this gain is dependent on the control mode.
7011 * Since this gain is multiplied by error in the input integrated over
7012 * time (in units of seconds), the units should be defined as units of
7013 * output per unit of integrated input error. For example, when
7014 * controlling velocity using a duty cycle closed loop, integrating
7015 * velocity over time results in rps * s = rotations. Therefore, the
7016 * units for the integral gain will be duty cycle per rotation of
7017 * accumulated error, or 1/rot.
7018 *
7019 * - Minimum Value: 0
7020 * - Maximum Value: 3.4e+38
7021 * - Default Value: 0
7022 * - Units:
7023 */
7024 units::dimensionless::scalar_t kI = 0;
7025 /**
7026 * \brief Derivative Gain.
7027 *
7028 * \details The units for this gain is dependent on the control mode.
7029 * Since this gain is multiplied by the derivative of error in the
7030 * input with respect to time (in units of seconds), the units should
7031 * be defined as units of output per unit of the differentiated input
7032 * error. For example, when controlling velocity using a duty cycle
7033 * closed loop, the derivative of velocity with respect to time is rot
7034 * per sec², which is acceleration. Therefore, the units for the
7035 * derivative gain will be duty cycle per unit of acceleration error,
7036 * or 1/(rot per sec²).
7037 *
7038 * - Minimum Value: 0
7039 * - Maximum Value: 3.4e+38
7040 * - Default Value: 0
7041 * - Units:
7042 */
7043 units::dimensionless::scalar_t kD = 0;
7044 /**
7045 * \brief Static Feedforward Gain.
7046 *
7047 * \details This is added to the closed loop output. The unit for this
7048 * constant is dependent on the control mode, typically fractional
7049 * duty cycle, voltage, or torque current.
7050 *
7051 * The sign is typically determined by reference velocity when using
7052 * position, velocity, and Motion Magic® closed loop modes. However,
7053 * when using position closed loop with zero velocity reference (no
7054 * motion profiling), the application can instead use the position
7055 * closed loop error by setting the Static Feedforward Sign
7056 * configuration parameter. When doing so, we recommend the minimal
7057 * amount of kS, otherwise the motor output may dither when closed
7058 * loop error is near zero.
7059 *
7060 * - Minimum Value: -512
7061 * - Maximum Value: 511
7062 * - Default Value: 0
7063 * - Units:
7064 */
7065 units::dimensionless::scalar_t kS = 0;
7066 /**
7067 * \brief Velocity Feedforward Gain.
7068 *
7069 * \details The units for this gain is dependent on the control mode.
7070 * Since this gain is multiplied by the requested velocity, the units
7071 * should be defined as units of output per unit of requested input
7072 * velocity. For example, when controlling velocity using a duty cycle
7073 * closed loop, the units for the velocity feedfoward gain will be
7074 * duty cycle per requested rps, or 1/rps.
7075 *
7076 * - Minimum Value: 0
7077 * - Maximum Value: 3.4e+38
7078 * - Default Value: 0
7079 * - Units:
7080 */
7081 units::dimensionless::scalar_t kV = 0;
7082 /**
7083 * \brief Acceleration Feedforward Gain.
7084 *
7085 * \details The units for this gain is dependent on the control mode.
7086 * Since this gain is multiplied by the requested acceleration, the
7087 * units should be defined as units of output per unit of requested
7088 * input acceleration. For example, when controlling velocity using a
7089 * duty cycle closed loop, the units for the acceleration feedfoward
7090 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7091 * sec²).
7092 *
7093 * - Minimum Value: 0
7094 * - Maximum Value: 3.4e+38
7095 * - Default Value: 0
7096 * - Units:
7097 */
7098 units::dimensionless::scalar_t kA = 0;
7099 /**
7100 * \brief Gravity Feedforward/Feedback Gain.
7101 *
7102 * \details This is added to the closed loop output. The sign is
7103 * determined by GravityType. The unit for this constant is dependent
7104 * on the control mode, typically fractional duty cycle, voltage, or
7105 * torque current.
7106 *
7107 * - Minimum Value: -512
7108 * - Maximum Value: 511
7109 * - Default Value: 0
7110 * - Units:
7111 */
7112 units::dimensionless::scalar_t kG = 0;
7113 /**
7114 * \brief Gravity Feedforward/Feedback Type.
7115 *
7116 * This determines the type of the gravity feedforward/feedback.
7117 *
7118 * Choose Elevator_Static for systems where the gravity feedforward is
7119 * constant, such as an elevator. The gravity feedforward output will
7120 * always be positive.
7121 *
7122 * Choose Arm_Cosine for systems where the gravity feedback is
7123 * dependent on the angular position of the mechanism, such as an arm.
7124 * The gravity feedback output will vary depending on the mechanism
7125 * angular position. Note that the sensor offset and ratios must be
7126 * configured so that the sensor position is 0 when the mechanism is
7127 * horizonal, and one rotation of the mechanism corresponds to one
7128 * rotation of the sensor position.
7129 *
7130 */
7132 /**
7133 * \brief Static Feedforward Sign during position closed loop.
7134 *
7135 * This determines the sign of the applied kS during position
7136 * closed-loop modes. The default behavior uses the velocity reference
7137 * sign. This works well with velocity closed loop, Motion Magic®
7138 * controls, and position closed loop when velocity reference is
7139 * specified (motion profiling).
7140 *
7141 * However, when using position closed loop with zero velocity
7142 * reference (no motion profiling), the application may want to apply
7143 * static feedforward based on the closed loop error sign instead.
7144 * When doing so, we recommend using the minimal amount of kS,
7145 * otherwise the motor output may dither when closed loop error is
7146 * near zero.
7147 *
7148 */
7150
7151 /**
7152 * \brief Modifies this configuration's kP parameter and returns itself for
7153 * method-chaining and easier to use config API.
7154 *
7155 * Proportional Gain.
7156 *
7157 * \details The units for this gain is dependent on the control mode.
7158 * Since this gain is multiplied by error in the input, the units
7159 * should be defined as units of output per unit of input error. For
7160 * example, when controlling velocity using a duty cycle closed loop,
7161 * the units for the proportional gain will be duty cycle per rps, or
7162 * 1/rps.
7163 *
7164 * - Minimum Value: 0
7165 * - Maximum Value: 3.4e+38
7166 * - Default Value: 0
7167 * - Units:
7168 *
7169 * \param newKP Parameter to modify
7170 * \returns Itself
7171 */
7172 constexpr Slot2Configs &WithKP(units::dimensionless::scalar_t newKP)
7173 {
7174 kP = std::move(newKP);
7175 return *this;
7176 }
7177
7178 /**
7179 * \brief Modifies this configuration's kI parameter and returns itself for
7180 * method-chaining and easier to use config API.
7181 *
7182 * Integral Gain.
7183 *
7184 * \details The units for this gain is dependent on the control mode.
7185 * Since this gain is multiplied by error in the input integrated over
7186 * time (in units of seconds), the units should be defined as units of
7187 * output per unit of integrated input error. For example, when
7188 * controlling velocity using a duty cycle closed loop, integrating
7189 * velocity over time results in rps * s = rotations. Therefore, the
7190 * units for the integral gain will be duty cycle per rotation of
7191 * accumulated error, or 1/rot.
7192 *
7193 * - Minimum Value: 0
7194 * - Maximum Value: 3.4e+38
7195 * - Default Value: 0
7196 * - Units:
7197 *
7198 * \param newKI Parameter to modify
7199 * \returns Itself
7200 */
7201 constexpr Slot2Configs &WithKI(units::dimensionless::scalar_t newKI)
7202 {
7203 kI = std::move(newKI);
7204 return *this;
7205 }
7206
7207 /**
7208 * \brief Modifies this configuration's kD parameter and returns itself for
7209 * method-chaining and easier to use config API.
7210 *
7211 * Derivative Gain.
7212 *
7213 * \details The units for this gain is dependent on the control mode.
7214 * Since this gain is multiplied by the derivative of error in the
7215 * input with respect to time (in units of seconds), the units should
7216 * be defined as units of output per unit of the differentiated input
7217 * error. For example, when controlling velocity using a duty cycle
7218 * closed loop, the derivative of velocity with respect to time is rot
7219 * per sec², which is acceleration. Therefore, the units for the
7220 * derivative gain will be duty cycle per unit of acceleration error,
7221 * or 1/(rot per sec²).
7222 *
7223 * - Minimum Value: 0
7224 * - Maximum Value: 3.4e+38
7225 * - Default Value: 0
7226 * - Units:
7227 *
7228 * \param newKD Parameter to modify
7229 * \returns Itself
7230 */
7231 constexpr Slot2Configs &WithKD(units::dimensionless::scalar_t newKD)
7232 {
7233 kD = std::move(newKD);
7234 return *this;
7235 }
7236
7237 /**
7238 * \brief Modifies this configuration's kS parameter and returns itself for
7239 * method-chaining and easier to use config API.
7240 *
7241 * Static Feedforward Gain.
7242 *
7243 * \details This is added to the closed loop output. The unit for this
7244 * constant is dependent on the control mode, typically fractional
7245 * duty cycle, voltage, or torque current.
7246 *
7247 * The sign is typically determined by reference velocity when using
7248 * position, velocity, and Motion Magic® closed loop modes. However,
7249 * when using position closed loop with zero velocity reference (no
7250 * motion profiling), the application can instead use the position
7251 * closed loop error by setting the Static Feedforward Sign
7252 * configuration parameter. When doing so, we recommend the minimal
7253 * amount of kS, otherwise the motor output may dither when closed
7254 * loop error is near zero.
7255 *
7256 * - Minimum Value: -512
7257 * - Maximum Value: 511
7258 * - Default Value: 0
7259 * - Units:
7260 *
7261 * \param newKS Parameter to modify
7262 * \returns Itself
7263 */
7264 constexpr Slot2Configs &WithKS(units::dimensionless::scalar_t newKS)
7265 {
7266 kS = std::move(newKS);
7267 return *this;
7268 }
7269
7270 /**
7271 * \brief Modifies this configuration's kV parameter and returns itself for
7272 * method-chaining and easier to use config API.
7273 *
7274 * Velocity Feedforward Gain.
7275 *
7276 * \details The units for this gain is dependent on the control mode.
7277 * Since this gain is multiplied by the requested velocity, the units
7278 * should be defined as units of output per unit of requested input
7279 * velocity. For example, when controlling velocity using a duty cycle
7280 * closed loop, the units for the velocity feedfoward gain will be
7281 * duty cycle per requested rps, or 1/rps.
7282 *
7283 * - Minimum Value: 0
7284 * - Maximum Value: 3.4e+38
7285 * - Default Value: 0
7286 * - Units:
7287 *
7288 * \param newKV Parameter to modify
7289 * \returns Itself
7290 */
7291 constexpr Slot2Configs &WithKV(units::dimensionless::scalar_t newKV)
7292 {
7293 kV = std::move(newKV);
7294 return *this;
7295 }
7296
7297 /**
7298 * \brief Modifies this configuration's kA parameter and returns itself for
7299 * method-chaining and easier to use config API.
7300 *
7301 * Acceleration Feedforward Gain.
7302 *
7303 * \details The units for this gain is dependent on the control mode.
7304 * Since this gain is multiplied by the requested acceleration, the
7305 * units should be defined as units of output per unit of requested
7306 * input acceleration. For example, when controlling velocity using a
7307 * duty cycle closed loop, the units for the acceleration feedfoward
7308 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7309 * sec²).
7310 *
7311 * - Minimum Value: 0
7312 * - Maximum Value: 3.4e+38
7313 * - Default Value: 0
7314 * - Units:
7315 *
7316 * \param newKA Parameter to modify
7317 * \returns Itself
7318 */
7319 constexpr Slot2Configs &WithKA(units::dimensionless::scalar_t newKA)
7320 {
7321 kA = std::move(newKA);
7322 return *this;
7323 }
7324
7325 /**
7326 * \brief Modifies this configuration's kG parameter and returns itself for
7327 * method-chaining and easier to use config API.
7328 *
7329 * Gravity Feedforward/Feedback Gain.
7330 *
7331 * \details This is added to the closed loop output. The sign is
7332 * determined by GravityType. The unit for this constant is dependent
7333 * on the control mode, typically fractional duty cycle, voltage, or
7334 * torque current.
7335 *
7336 * - Minimum Value: -512
7337 * - Maximum Value: 511
7338 * - Default Value: 0
7339 * - Units:
7340 *
7341 * \param newKG Parameter to modify
7342 * \returns Itself
7343 */
7344 constexpr Slot2Configs &WithKG(units::dimensionless::scalar_t newKG)
7345 {
7346 kG = std::move(newKG);
7347 return *this;
7348 }
7349
7350 /**
7351 * \brief Modifies this configuration's GravityType parameter and returns itself for
7352 * method-chaining and easier to use config API.
7353 *
7354 * Gravity Feedforward/Feedback Type.
7355 *
7356 * This determines the type of the gravity feedforward/feedback.
7357 *
7358 * Choose Elevator_Static for systems where the gravity feedforward is
7359 * constant, such as an elevator. The gravity feedforward output will
7360 * always be positive.
7361 *
7362 * Choose Arm_Cosine for systems where the gravity feedback is
7363 * dependent on the angular position of the mechanism, such as an arm.
7364 * The gravity feedback output will vary depending on the mechanism
7365 * angular position. Note that the sensor offset and ratios must be
7366 * configured so that the sensor position is 0 when the mechanism is
7367 * horizonal, and one rotation of the mechanism corresponds to one
7368 * rotation of the sensor position.
7369 *
7370 *
7371 * \param newGravityType Parameter to modify
7372 * \returns Itself
7373 */
7375 {
7376 GravityType = std::move(newGravityType);
7377 return *this;
7378 }
7379
7380 /**
7381 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
7382 * method-chaining and easier to use config API.
7383 *
7384 * Static Feedforward Sign during position closed loop.
7385 *
7386 * This determines the sign of the applied kS during position
7387 * closed-loop modes. The default behavior uses the velocity reference
7388 * sign. This works well with velocity closed loop, Motion Magic®
7389 * controls, and position closed loop when velocity reference is
7390 * specified (motion profiling).
7391 *
7392 * However, when using position closed loop with zero velocity
7393 * reference (no motion profiling), the application may want to apply
7394 * static feedforward based on the closed loop error sign instead.
7395 * When doing so, we recommend using the minimal amount of kS,
7396 * otherwise the motor output may dither when closed loop error is
7397 * near zero.
7398 *
7399 *
7400 * \param newStaticFeedforwardSign Parameter to modify
7401 * \returns Itself
7402 */
7404 {
7405 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
7406 return *this;
7407 }
7408
7409 static Slot2Configs From(const SlotConfigs &value);
7410
7411 std::string ToString() const override
7412 {
7413 std::stringstream ss;
7414 ss << "Config Group: Slot2" << std::endl;
7415 ss << " kP: " << kP.to<double>() << std::endl;
7416 ss << " kI: " << kI.to<double>() << std::endl;
7417 ss << " kD: " << kD.to<double>() << std::endl;
7418 ss << " kS: " << kS.to<double>() << std::endl;
7419 ss << " kV: " << kV.to<double>() << std::endl;
7420 ss << " kA: " << kA.to<double>() << std::endl;
7421 ss << " kG: " << kG.to<double>() << std::endl;
7422 ss << " GravityType: " << GravityType << std::endl;
7423 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
7424 return ss.str();
7425 }
7426
7427 std::string Serialize() const override
7428 {
7429 std::stringstream ss;
7430 char *ref;
7431 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kP, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7432 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kI, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7433 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kD, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7434 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kS, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7435 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kV, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7436 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kA, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7437 c_ctre_phoenix6_serialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kG, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7438 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kG_Type, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7439 c_ctre_phoenix6_serialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7440 return ss.str();
7441 }
7442
7443 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
7444 {
7445 const char *string_c_str = to_deserialize.c_str();
7446 size_t string_length = to_deserialize.length();
7447 double kPVal = kP.to<double>();
7448 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kP, string_c_str, string_length, &kPVal);
7449 kP = units::dimensionless::scalar_t{kPVal};
7450 double kIVal = kI.to<double>();
7451 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kI, string_c_str, string_length, &kIVal);
7452 kI = units::dimensionless::scalar_t{kIVal};
7453 double kDVal = kD.to<double>();
7454 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kD, string_c_str, string_length, &kDVal);
7455 kD = units::dimensionless::scalar_t{kDVal};
7456 double kSVal = kS.to<double>();
7457 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kS, string_c_str, string_length, &kSVal);
7458 kS = units::dimensionless::scalar_t{kSVal};
7459 double kVVal = kV.to<double>();
7460 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kV, string_c_str, string_length, &kVVal);
7461 kV = units::dimensionless::scalar_t{kVVal};
7462 double kAVal = kA.to<double>();
7463 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kA, string_c_str, string_length, &kAVal);
7464 kA = units::dimensionless::scalar_t{kAVal};
7465 double kGVal = kG.to<double>();
7466 c_ctre_phoenix6_deserialize_double(ctre::phoenix6::spns::SpnValue::Slot2_kG, string_c_str, string_length, &kGVal);
7467 kG = units::dimensionless::scalar_t{kGVal};
7468 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kG_Type, string_c_str, string_length, &GravityType.value);
7469 c_ctre_phoenix6_deserialize_int(ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign, string_c_str, string_length, &StaticFeedforwardSign.value);
7470 return 0;
7471 }
7472};
7473
7474/**
7475 * \brief Gains for the specified slot.
7476 *
7477 * \details If this slot is selected, these gains are used in closed
7478 * loop control requests.
7479 */
7481{
7482 struct SlotSpns
7483 {
7484 int kPSpn;
7485 int kISpn;
7486 int kDSpn;
7487 int kSSpn;
7488 int kVSpn;
7489 int kASpn;
7490 int kGSpn;
7491 int GravityTypeSpn;
7492 int StaticFeedforwardSignSpn;
7493 };
7494
7495 static inline std::map<int, SlotSpns> const genericMap{
7496 {0, SlotSpns{
7497 ctre::phoenix6::spns::SpnValue::Slot0_kP,
7498 ctre::phoenix6::spns::SpnValue::Slot0_kI,
7499 ctre::phoenix6::spns::SpnValue::Slot0_kD,
7500 ctre::phoenix6::spns::SpnValue::Slot0_kS,
7501 ctre::phoenix6::spns::SpnValue::Slot0_kV,
7502 ctre::phoenix6::spns::SpnValue::Slot0_kA,
7503 ctre::phoenix6::spns::SpnValue::Slot0_kG,
7504 ctre::phoenix6::spns::SpnValue::Slot0_kG_Type,
7505 ctre::phoenix6::spns::SpnValue::Slot0_kS_Sign,
7506 }},
7507
7508 {1, SlotSpns{
7509 ctre::phoenix6::spns::SpnValue::Slot1_kP,
7510 ctre::phoenix6::spns::SpnValue::Slot1_kI,
7511 ctre::phoenix6::spns::SpnValue::Slot1_kD,
7512 ctre::phoenix6::spns::SpnValue::Slot1_kS,
7513 ctre::phoenix6::spns::SpnValue::Slot1_kV,
7514 ctre::phoenix6::spns::SpnValue::Slot1_kA,
7515 ctre::phoenix6::spns::SpnValue::Slot1_kG,
7516 ctre::phoenix6::spns::SpnValue::Slot1_kG_Type,
7517 ctre::phoenix6::spns::SpnValue::Slot1_kS_Sign,
7518 }},
7519
7520 {2, SlotSpns{
7521 ctre::phoenix6::spns::SpnValue::Slot2_kP,
7522 ctre::phoenix6::spns::SpnValue::Slot2_kI,
7523 ctre::phoenix6::spns::SpnValue::Slot2_kD,
7524 ctre::phoenix6::spns::SpnValue::Slot2_kS,
7525 ctre::phoenix6::spns::SpnValue::Slot2_kV,
7526 ctre::phoenix6::spns::SpnValue::Slot2_kA,
7527 ctre::phoenix6::spns::SpnValue::Slot2_kG,
7528 ctre::phoenix6::spns::SpnValue::Slot2_kG_Type,
7529 ctre::phoenix6::spns::SpnValue::Slot2_kS_Sign,
7530 }},
7531
7532 };
7533
7534public:
7535 constexpr SlotConfigs() = default;
7536
7537 /**
7538 * \brief Proportional Gain.
7539 *
7540 * \details The units for this gain is dependent on the control mode.
7541 * Since this gain is multiplied by error in the input, the units
7542 * should be defined as units of output per unit of input error. For
7543 * example, when controlling velocity using a duty cycle closed loop,
7544 * the units for the proportional gain will be duty cycle per rps of
7545 * error, or 1/rps.
7546 *
7547 * - Minimum Value: 0
7548 * - Maximum Value: 3.4e+38
7549 * - Default Value: 0
7550 * - Units:
7551 */
7552 units::dimensionless::scalar_t kP = 0;
7553 /**
7554 * \brief Integral Gain.
7555 *
7556 * \details The units for this gain is dependent on the control mode.
7557 * Since this gain is multiplied by error in the input integrated over
7558 * time (in units of seconds), the units should be defined as units of
7559 * output per unit of integrated input error. For example, when
7560 * controlling velocity using a duty cycle closed loop, integrating
7561 * velocity over time results in rps * s = rotations. Therefore, the
7562 * units for the integral gain will be duty cycle per rotation of
7563 * accumulated error, or 1/rot.
7564 *
7565 * - Minimum Value: 0
7566 * - Maximum Value: 3.4e+38
7567 * - Default Value: 0
7568 * - Units:
7569 */
7570 units::dimensionless::scalar_t kI = 0;
7571 /**
7572 * \brief Derivative Gain.
7573 *
7574 * \details The units for this gain is dependent on the control mode.
7575 * Since this gain is multiplied by the derivative of error in the
7576 * input with respect to time (in units of seconds), the units should
7577 * be defined as units of output per unit of the differentiated input
7578 * error. For example, when controlling velocity using a duty cycle
7579 * closed loop, the derivative of velocity with respect to time is rot
7580 * per sec², which is acceleration. Therefore, the units for the
7581 * derivative gain will be duty cycle per unit of acceleration error,
7582 * or 1/(rot per sec²).
7583 *
7584 * - Minimum Value: 0
7585 * - Maximum Value: 3.4e+38
7586 * - Default Value: 0
7587 * - Units:
7588 */
7589 units::dimensionless::scalar_t kD = 0;
7590 /**
7591 * \brief Static Feedforward Gain.
7592 *
7593 * \details This is added to the closed loop output. The unit for this
7594 * constant is dependent on the control mode, typically fractional
7595 * duty cycle, voltage, or torque current.
7596 *
7597 * The sign is typically determined by reference velocity when using
7598 * position, velocity, and Motion Magic® closed loop modes. However,
7599 * when using position closed loop with zero velocity reference (no
7600 * motion profiling), the application can instead use the position
7601 * closed loop error by setting the Static Feedforward Sign
7602 * configuration parameter. When doing so, we recommend the minimal
7603 * amount of kS, otherwise the motor output may dither when closed
7604 * loop error is near zero.
7605 *
7606 * - Minimum Value: -512
7607 * - Maximum Value: 511
7608 * - Default Value: 0
7609 * - Units:
7610 */
7611 units::dimensionless::scalar_t kS = 0;
7612 /**
7613 * \brief Velocity Feedforward Gain.
7614 *
7615 * \details The units for this gain is dependent on the control mode.
7616 * Since this gain is multiplied by the requested velocity, the units
7617 * should be defined as units of output per unit of requested input
7618 * velocity. For example, when controlling velocity using a duty cycle
7619 * closed loop, the units for the velocity feedfoward gain will be
7620 * duty cycle per requested rps, or 1/rps.
7621 *
7622 * - Minimum Value: 0
7623 * - Maximum Value: 3.4e+38
7624 * - Default Value: 0
7625 * - Units:
7626 */
7627 units::dimensionless::scalar_t kV = 0;
7628 /**
7629 * \brief Acceleration Feedforward Gain.
7630 *
7631 * \details The units for this gain is dependent on the control mode.
7632 * Since this gain is multiplied by the requested acceleration, the
7633 * units should be defined as units of output per unit of requested
7634 * input acceleration. For example, when controlling velocity using a
7635 * duty cycle closed loop, the units for the acceleration feedfoward
7636 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7637 * sec²).
7638 *
7639 * - Minimum Value: 0
7640 * - Maximum Value: 3.4e+38
7641 * - Default Value: 0
7642 * - Units:
7643 */
7644 units::dimensionless::scalar_t kA = 0;
7645 /**
7646 * \brief Gravity Feedforward/Feedback Gain.
7647 *
7648 * \details This is added to the closed loop output. The sign is
7649 * determined by GravityType. The unit for this constant is dependent
7650 * on the control mode, typically fractional duty cycle, voltage, or
7651 * torque current.
7652 *
7653 * - Minimum Value: -512
7654 * - Maximum Value: 511
7655 * - Default Value: 0
7656 * - Units:
7657 */
7658 units::dimensionless::scalar_t kG = 0;
7659 /**
7660 * \brief Gravity Feedforward/Feedback Type.
7661 *
7662 * This determines the type of the gravity feedforward/feedback.
7663 *
7664 * Choose Elevator_Static for systems where the gravity feedforward is
7665 * constant, such as an elevator. The gravity feedforward output will
7666 * always have the same sign.
7667 *
7668 * Choose Arm_Cosine for systems where the gravity feedback is
7669 * dependent on the angular position of the mechanism, such as an arm.
7670 * The gravity feedback output will vary depending on the mechanism
7671 * angular position. Note that the sensor offset and ratios must be
7672 * configured so that the sensor reports a position of 0 when the
7673 * mechanism is horizonal (parallel to the ground), and the reported
7674 * sensor position is 1:1 with the mechanism.
7675 *
7676 */
7678 /**
7679 * \brief Static Feedforward Sign during position closed loop.
7680 *
7681 * This determines the sign of the applied kS during position
7682 * closed-loop modes. The default behavior uses the velocity reference
7683 * sign. This works well with velocity closed loop, Motion Magic®
7684 * controls, and position closed loop when velocity reference is
7685 * specified (motion profiling).
7686 *
7687 * However, when using position closed loop with zero velocity
7688 * reference (no motion profiling), the application may want to apply
7689 * static feedforward based on the sign of closed loop error instead.
7690 * When doing so, we recommend using the minimal amount of kS,
7691 * otherwise the motor output may dither when closed loop error is
7692 * near zero.
7693 *
7694 */
7696
7697 /**
7698 * \brief Modifies this configuration's kP parameter and returns itself for
7699 * method-chaining and easier to use config API.
7700 *
7701 * Proportional Gain.
7702 *
7703 * \details The units for this gain is dependent on the control mode.
7704 * Since this gain is multiplied by error in the input, the units
7705 * should be defined as units of output per unit of input error. For
7706 * example, when controlling velocity using a duty cycle closed loop,
7707 * the units for the proportional gain will be duty cycle per rps of
7708 * error, or 1/rps.
7709 *
7710 * - Minimum Value: 0
7711 * - Maximum Value: 3.4e+38
7712 * - Default Value: 0
7713 * - Units:
7714 *
7715 * \param newKP Parameter to modify
7716 * \returns Itself
7717 */
7718 constexpr SlotConfigs &WithKP(units::dimensionless::scalar_t newKP)
7719 {
7720 kP = std::move(newKP);
7721 return *this;
7722 }
7723
7724 /**
7725 * \brief Modifies this configuration's kI parameter and returns itself for
7726 * method-chaining and easier to use config API.
7727 *
7728 * Integral Gain.
7729 *
7730 * \details The units for this gain is dependent on the control mode.
7731 * Since this gain is multiplied by error in the input integrated over
7732 * time (in units of seconds), the units should be defined as units of
7733 * output per unit of integrated input error. For example, when
7734 * controlling velocity using a duty cycle closed loop, integrating
7735 * velocity over time results in rps * s = rotations. Therefore, the
7736 * units for the integral gain will be duty cycle per rotation of
7737 * accumulated error, or 1/rot.
7738 *
7739 * - Minimum Value: 0
7740 * - Maximum Value: 3.4e+38
7741 * - Default Value: 0
7742 * - Units:
7743 *
7744 * \param newKI Parameter to modify
7745 * \returns Itself
7746 */
7747 constexpr SlotConfigs &WithKI(units::dimensionless::scalar_t newKI)
7748 {
7749 kI = std::move(newKI);
7750 return *this;
7751 }
7752
7753 /**
7754 * \brief Modifies this configuration's kD parameter and returns itself for
7755 * method-chaining and easier to use config API.
7756 *
7757 * Derivative Gain.
7758 *
7759 * \details The units for this gain is dependent on the control mode.
7760 * Since this gain is multiplied by the derivative of error in the
7761 * input with respect to time (in units of seconds), the units should
7762 * be defined as units of output per unit of the differentiated input
7763 * error. For example, when controlling velocity using a duty cycle
7764 * closed loop, the derivative of velocity with respect to time is rot
7765 * per sec², which is acceleration. Therefore, the units for the
7766 * derivative gain will be duty cycle per unit of acceleration error,
7767 * or 1/(rot per sec²).
7768 *
7769 * - Minimum Value: 0
7770 * - Maximum Value: 3.4e+38
7771 * - Default Value: 0
7772 * - Units:
7773 *
7774 * \param newKD Parameter to modify
7775 * \returns Itself
7776 */
7777 constexpr SlotConfigs &WithKD(units::dimensionless::scalar_t newKD)
7778 {
7779 kD = std::move(newKD);
7780 return *this;
7781 }
7782
7783 /**
7784 * \brief Modifies this configuration's kS parameter and returns itself for
7785 * method-chaining and easier to use config API.
7786 *
7787 * Static Feedforward Gain.
7788 *
7789 * \details This is added to the closed loop output. The unit for this
7790 * constant is dependent on the control mode, typically fractional
7791 * duty cycle, voltage, or torque current.
7792 *
7793 * The sign is typically determined by reference velocity when using
7794 * position, velocity, and Motion Magic® closed loop modes. However,
7795 * when using position closed loop with zero velocity reference (no
7796 * motion profiling), the application can instead use the position
7797 * closed loop error by setting the Static Feedforward Sign
7798 * configuration parameter. When doing so, we recommend the minimal
7799 * amount of kS, otherwise the motor output may dither when closed
7800 * loop error is near zero.
7801 *
7802 * - Minimum Value: -512
7803 * - Maximum Value: 511
7804 * - Default Value: 0
7805 * - Units:
7806 *
7807 * \param newKS Parameter to modify
7808 * \returns Itself
7809 */
7810 constexpr SlotConfigs &WithKS(units::dimensionless::scalar_t newKS)
7811 {
7812 kS = std::move(newKS);
7813 return *this;
7814 }
7815
7816 /**
7817 * \brief Modifies this configuration's kV parameter and returns itself for
7818 * method-chaining and easier to use config API.
7819 *
7820 * Velocity Feedforward Gain.
7821 *
7822 * \details The units for this gain is dependent on the control mode.
7823 * Since this gain is multiplied by the requested velocity, the units
7824 * should be defined as units of output per unit of requested input
7825 * velocity. For example, when controlling velocity using a duty cycle
7826 * closed loop, the units for the velocity feedfoward gain will be
7827 * duty cycle per requested rps, or 1/rps.
7828 *
7829 * - Minimum Value: 0
7830 * - Maximum Value: 3.4e+38
7831 * - Default Value: 0
7832 * - Units:
7833 *
7834 * \param newKV Parameter to modify
7835 * \returns Itself
7836 */
7837 constexpr SlotConfigs &WithKV(units::dimensionless::scalar_t newKV)
7838 {
7839 kV = std::move(newKV);
7840 return *this;
7841 }
7842
7843 /**
7844 * \brief Modifies this configuration's kA parameter and returns itself for
7845 * method-chaining and easier to use config API.
7846 *
7847 * Acceleration Feedforward Gain.
7848 *
7849 * \details The units for this gain is dependent on the control mode.
7850 * Since this gain is multiplied by the requested acceleration, the
7851 * units should be defined as units of output per unit of requested
7852 * input acceleration. For example, when controlling velocity using a
7853 * duty cycle closed loop, the units for the acceleration feedfoward
7854 * gain will be duty cycle per requested rot per sec², or 1/(rot per
7855 * sec²).
7856 *
7857 * - Minimum Value: 0
7858 * - Maximum Value: 3.4e+38
7859 * - Default Value: 0
7860 * - Units:
7861 *
7862 * \param newKA Parameter to modify
7863 * \returns Itself
7864 */
7865 constexpr SlotConfigs &WithKA(units::dimensionless::scalar_t newKA)
7866 {
7867 kA = std::move(newKA);
7868 return *this;
7869 }
7870
7871 /**
7872 * \brief Modifies this configuration's kG parameter and returns itself for
7873 * method-chaining and easier to use config API.
7874 *
7875 * Gravity Feedforward/Feedback Gain.
7876 *
7877 * \details This is added to the closed loop output. The sign is
7878 * determined by GravityType. The unit for this constant is dependent
7879 * on the control mode, typically fractional duty cycle, voltage, or
7880 * torque current.
7881 *
7882 * - Minimum Value: -512
7883 * - Maximum Value: 511
7884 * - Default Value: 0
7885 * - Units:
7886 *
7887 * \param newKG Parameter to modify
7888 * \returns Itself
7889 */
7890 constexpr SlotConfigs &WithKG(units::dimensionless::scalar_t newKG)
7891 {
7892 kG = std::move(newKG);
7893 return *this;
7894 }
7895
7896 /**
7897 * \brief Modifies this configuration's GravityType parameter and returns itself for
7898 * method-chaining and easier to use config API.
7899 *
7900 * Gravity Feedforward/Feedback Type.
7901 *
7902 * This determines the type of the gravity feedforward/feedback.
7903 *
7904 * Choose Elevator_Static for systems where the gravity feedforward is
7905 * constant, such as an elevator. The gravity feedforward output will
7906 * always have the same sign.
7907 *
7908 * Choose Arm_Cosine for systems where the gravity feedback is
7909 * dependent on the angular position of the mechanism, such as an arm.
7910 * The gravity feedback output will vary depending on the mechanism
7911 * angular position. Note that the sensor offset and ratios must be
7912 * configured so that the sensor reports a position of 0 when the
7913 * mechanism is horizonal (parallel to the ground), and the reported
7914 * sensor position is 1:1 with the mechanism.
7915 *
7916 *
7917 * \param newGravityType Parameter to modify
7918 * \returns Itself
7919 */
7921 {
7922 GravityType = std::move(newGravityType);
7923 return *this;
7924 }
7925
7926 /**
7927 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
7928 * method-chaining and easier to use config API.
7929 *
7930 * Static Feedforward Sign during position closed loop.
7931 *
7932 * This determines the sign of the applied kS during position
7933 * closed-loop modes. The default behavior uses the velocity reference
7934 * sign. This works well with velocity closed loop, Motion Magic®
7935 * controls, and position closed loop when velocity reference is
7936 * specified (motion profiling).
7937 *
7938 * However, when using position closed loop with zero velocity
7939 * reference (no motion profiling), the application may want to apply
7940 * static feedforward based on the sign of closed loop error instead.
7941 * When doing so, we recommend using the minimal amount of kS,
7942 * otherwise the motor output may dither when closed loop error is
7943 * near zero.
7944 *
7945 *
7946 * \param newStaticFeedforwardSign Parameter to modify
7947 * \returns Itself
7948 */
7950 {
7951 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
7952 return *this;
7953 }
7954
7955
7956 /**
7957 * \brief Chooses which slot these configs are for.
7958 */
7959 int SlotNumber = 0;
7960
7961 static SlotConfigs From(const Slot0Configs &value);
7962 static SlotConfigs From(const Slot1Configs &value);
7963 static SlotConfigs From(const Slot2Configs &value);
7964
7965 std::string ToString() const
7966 {
7967 std::stringstream ss;
7968 ss << "Config Group: Slot" << std::endl;
7969 ss << " kP: " << kP.to<double>() << std::endl;
7970 ss << " kI: " << kI.to<double>() << std::endl;
7971 ss << " kD: " << kD.to<double>() << std::endl;
7972 ss << " kS: " << kS.to<double>() << std::endl;
7973 ss << " kV: " << kV.to<double>() << std::endl;
7974 ss << " kA: " << kA.to<double>() << std::endl;
7975 ss << " kG: " << kG.to<double>() << std::endl;
7976 ss << " GravityType: " << GravityType << std::endl;
7977 ss << " StaticFeedforwardSign: " << StaticFeedforwardSign << std::endl;
7978 return ss.str();
7979 }
7980
7981 std::string Serialize() const
7982 {
7983 std::stringstream ss;
7984 SlotSpns currentSpns = genericMap.at(SlotNumber);
7985 char *ref;
7986 c_ctre_phoenix6_serialize_double(currentSpns.kPSpn, kP.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7987 c_ctre_phoenix6_serialize_double(currentSpns.kISpn, kI.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7988 c_ctre_phoenix6_serialize_double(currentSpns.kDSpn, kD.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7989 c_ctre_phoenix6_serialize_double(currentSpns.kSSpn, kS.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7990 c_ctre_phoenix6_serialize_double(currentSpns.kVSpn, kV.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7991 c_ctre_phoenix6_serialize_double(currentSpns.kASpn, kA.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7992 c_ctre_phoenix6_serialize_double(currentSpns.kGSpn, kG.to<double>(), &ref); if (ref != nullptr) { ss << ref; free(ref); }
7993 c_ctre_phoenix6_serialize_int(currentSpns.GravityTypeSpn, GravityType.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7994 c_ctre_phoenix6_serialize_int(currentSpns.StaticFeedforwardSignSpn, StaticFeedforwardSign.value, &ref); if (ref != nullptr) { ss << ref; free(ref); }
7995 return ss.str();
7996 }
7997
7998 ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
7999 {
8000 const char *string_c_str = to_deserialize.c_str();
8001 size_t string_length = to_deserialize.length();
8002 SlotSpns currentSpns = genericMap.at(SlotNumber);
8003 double kPVal = kP.to<double>();
8004 c_ctre_phoenix6_deserialize_double(currentSpns.kPSpn, string_c_str, string_length, &kPVal);
8005 kP = units::dimensionless::scalar_t{kPVal};
8006 double kIVal = kI.to<double>();
8007 c_ctre_phoenix6_deserialize_double(currentSpns.kISpn, string_c_str, string_length, &kIVal);
8008 kI = units::dimensionless::scalar_t{kIVal};
8009 double kDVal = kD.to<double>();
8010 c_ctre_phoenix6_deserialize_double(currentSpns.kDSpn, string_c_str, string_length, &kDVal);
8011 kD = units::dimensionless::scalar_t{kDVal};
8012 double kSVal = kS.to<double>();
8013 c_ctre_phoenix6_deserialize_double(currentSpns.kSSpn, string_c_str, string_length, &kSVal);
8014 kS = units::dimensionless::scalar_t{kSVal};
8015 double kVVal = kV.to<double>();
8016 c_ctre_phoenix6_deserialize_double(currentSpns.kVSpn, string_c_str, string_length, &kVVal);
8017 kV = units::dimensionless::scalar_t{kVVal};
8018 double kAVal = kA.to<double>();
8019 c_ctre_phoenix6_deserialize_double(currentSpns.kASpn, string_c_str, string_length, &kAVal);
8020 kA = units::dimensionless::scalar_t{kAVal};
8021 double kGVal = kG.to<double>();
8022 c_ctre_phoenix6_deserialize_double(currentSpns.kGSpn, string_c_str, string_length, &kGVal);
8023 kG = units::dimensionless::scalar_t{kGVal};
8024 c_ctre_phoenix6_deserialize_int(currentSpns.GravityTypeSpn, string_c_str, string_length, &GravityType.value);
8025 c_ctre_phoenix6_deserialize_int(currentSpns.StaticFeedforwardSignSpn, string_c_str, string_length, &StaticFeedforwardSign.value);
8026 return 0;
8027 }
8028};
8029
8030
8031}
8032}
8033}
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:3989
bool BeepOnConfig
If true, the TalonFX will beep during configuration API calls if device is disabled.
Definition Configs.hpp:4010
bool AllowMusicDurDisable
If true, the TalonFX will allow Orchestra and MusicTone requests during disabled state.
Definition Configs.hpp:4020
std::string Serialize() const override
Definition Configs.hpp:4094
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4104
std::string ToString() const override
Definition Configs.hpp:4084
constexpr AudioConfigs & WithBeepOnBoot(bool newBeepOnBoot)
Modifies this configuration's BeepOnBoot parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:4035
constexpr AudioConfigs & WithAllowMusicDurDisable(bool newAllowMusicDurDisable)
Modifies this configuration's AllowMusicDurDisable parameter and returns itself for method-chaining a...
Definition Configs.hpp:4076
constexpr AudioConfigs & WithBeepOnConfig(bool newBeepOnConfig)
Modifies this configuration's BeepOnConfig parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4055
bool BeepOnBoot
If true, the TalonFX will beep during boot-up.
Definition Configs.hpp:4001
Configs that affect general behavior during closed-looping.
Definition Configs.hpp:4648
bool ContinuousWrap
Wrap position error within [-0.5,+0.5) mechanism rotations.
Definition Configs.hpp:4664
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4708
constexpr ClosedLoopGeneralConfigs & WithContinuousWrap(bool newContinuousWrap)
Modifies this configuration's ContinuousWrap parameter and returns itself for method-chaining and eas...
Definition Configs.hpp:4684
std::string ToString() const override
Definition Configs.hpp:4692
std::string Serialize() const override
Definition Configs.hpp:4700
Configs that affect the closed-loop control of this motor controller.
Definition Configs.hpp:3220
constexpr ClosedLoopRampsConfigs & WithDutyCycleClosedLoopRampPeriod(units::time::second_t newDutyCycleClosedLoopRampPeriod)
Modifies this configuration's DutyCycleClosedLoopRampPeriod parameter and returns itself for method-c...
Definition Configs.hpp:3301
std::string Serialize() const override
Definition Configs.hpp:3378
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:3240
constexpr ClosedLoopRampsConfigs & WithTorqueClosedLoopRampPeriod(units::time::second_t newTorqueClosedLoopRampPeriod)
Modifies this configuration's TorqueClosedLoopRampPeriod parameter and returns itself for method-chai...
Definition Configs.hpp:3360
constexpr ClosedLoopRampsConfigs & WithVoltageClosedLoopRampPeriod(units::time::second_t newVoltageClosedLoopRampPeriod)
Modifies this configuration's VoltageClosedLoopRampPeriod parameter and returns itself for method-cha...
Definition Configs.hpp:3329
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:3277
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:3257
std::string ToString() const override
Definition Configs.hpp:3368
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3388
Configs that determine motor selection and commutation.
Definition Configs.hpp:5206
std::string ToString() const override
Definition Configs.hpp:5300
constexpr CommutationConfigs & WithAdvancedHallSupport(signals::AdvancedHallSupportValue newAdvancedHallSupport)
Modifies this configuration's AdvancedHallSupport parameter and returns itself for method-chaining an...
Definition Configs.hpp:5252
signals::BrushedMotorWiringValue BrushedMotorWiring
If a brushed motor is selected with Motor Arrangement, this config determines which of three leads to...
Definition Configs.hpp:5236
signals::AdvancedHallSupportValue AdvancedHallSupport
Requires Phoenix Pro; Improves commutation and velocity measurement for motors with hall sensors.
Definition Configs.hpp:5218
std::string Serialize() const override
Definition Configs.hpp:5310
signals::MotorArrangementValue MotorArrangement
Selects the motor and motor connections used with Talon.
Definition Configs.hpp:5230
constexpr CommutationConfigs & WithBrushedMotorWiring(signals::BrushedMotorWiringValue newBrushedMotorWiring)
Modifies this configuration's BrushedMotorWiring parameter and returns itself for method-chaining and...
Definition Configs.hpp:5292
constexpr CommutationConfigs & WithMotorArrangement(signals::MotorArrangementValue newMotorArrangement)
Modifies this configuration's MotorArrangement parameter and returns itself for method-chaining and e...
Definition Configs.hpp:5275
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5320
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:4544
std::string ToString() const override
Definition Configs.hpp:4613
int CustomParam0
Custom parameter 0.
Definition Configs.hpp:4557
std::string Serialize() const override
Definition Configs.hpp:4622
int CustomParam1
Custom parameter 1.
Definition Configs.hpp:4567
constexpr CustomParamsConfigs & WithCustomParam0(int newCustomParam0)
Modifies this configuration's CustomParam0 parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4584
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4631
constexpr CustomParamsConfigs & WithCustomParam1(int newCustomParam1)
Modifies this configuration's CustomParam1 parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:4605
Configs related to constants used for differential control of a mechanism.
Definition Configs.hpp:2908
units::current::ampere_t PeakDifferentialTorqueCurrent
Maximum differential output during torque current based differential control modes.
Definition Configs.hpp:2941
std::string Serialize() const override
Definition Configs.hpp:3018
std::string ToString() const override
Definition Configs.hpp:3008
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3028
constexpr DifferentialConstantsConfigs & WithPeakDifferentialVoltage(units::voltage::volt_t newPeakDifferentialVoltage)
Modifies this configuration's PeakDifferentialVoltage parameter and returns itself for method-chainin...
Definition Configs.hpp:2979
units::dimensionless::scalar_t PeakDifferentialDutyCycle
Maximum differential output during duty cycle based differential control modes.
Definition Configs.hpp:2921
constexpr DifferentialConstantsConfigs & WithPeakDifferentialTorqueCurrent(units::current::ampere_t newPeakDifferentialTorqueCurrent)
Modifies this configuration's PeakDifferentialTorqueCurrent parameter and returns itself for method-c...
Definition Configs.hpp:3000
constexpr DifferentialConstantsConfigs & WithPeakDifferentialDutyCycle(units::dimensionless::scalar_t newPeakDifferentialDutyCycle)
Modifies this configuration's PeakDifferentialDutyCycle parameter and returns itself for method-chain...
Definition Configs.hpp:2958
units::voltage::volt_t PeakDifferentialVoltage
Maximum differential output during voltage based differential control modes.
Definition Configs.hpp:2931
Configs related to sensors used for differential control of a mechanism.
Definition Configs.hpp:2729
constexpr DifferentialSensorsConfigs & WithDifferentialTalonFXSensorID(int newDifferentialTalonFXSensorID)
Modifies this configuration's DifferentialTalonFXSensorID parameter and returns itself for method-cha...
Definition Configs.hpp:2839
constexpr DifferentialSensorsConfigs & WithDifferentialSensorSource(signals::DifferentialSensorSourceValue newDifferentialSensorSource)
Modifies this configuration's DifferentialSensorSource parameter and returns itself for method-chaini...
Definition Configs.hpp:2818
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:2889
std::string Serialize() const override
Definition Configs.hpp:2879
std::string ToString() const override
Definition Configs.hpp:2869
signals::DifferentialSensorSourceValue DifferentialSensorSource
Choose what sensor source is used for differential control of a mechanism.
Definition Configs.hpp:2761
int DifferentialRemoteSensorID
Device ID of which remote sensor to use on the differential axis.
Definition Configs.hpp:2782
constexpr DifferentialSensorsConfigs & WithDifferentialRemoteSensorID(int newDifferentialRemoteSensorID)
Modifies this configuration's DifferentialRemoteSensorID parameter and returns itself for method-chai...
Definition Configs.hpp:2861
int DifferentialTalonFXSensorID
Device ID of which remote Talon FX to use.
Definition Configs.hpp:2771
Configs related to CANdi digital I/O settings.
Definition Configs.hpp:5339
signals::S1CloseStateValue S1CloseState
What value the Signal 1 input (S1IN) needs to be for the CANdi to detect as Closed.
Definition Configs.hpp:5361
constexpr DigitalInputsConfigs & WithS2FloatState(signals::S2FloatStateValue newS2FloatState)
Modifies this configuration's S2FloatState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5398
signals::S2FloatStateValue S2FloatState
The floating state of the Signal 2 input (S2IN).
Definition Configs.hpp:5352
constexpr DigitalInputsConfigs & WithS2CloseState(signals::S2CloseStateValue newS2CloseState)
Modifies this configuration's S2CloseState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5438
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5468
std::string ToString() const override
Definition Configs.hpp:5446
signals::S2CloseStateValue S2CloseState
What value the Signal 2 input (S2IN) needs to be for the CANdi to detect as Closed.
Definition Configs.hpp:5370
constexpr DigitalInputsConfigs & WithS1CloseState(signals::S1CloseStateValue newS1CloseState)
Modifies this configuration's S1CloseState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5418
std::string Serialize() const override
Definition Configs.hpp:5457
signals::S1FloatStateValue S1FloatState
The floating state of the Signal 1 input (S1IN).
Definition Configs.hpp:5347
constexpr DigitalInputsConfigs & WithS1FloatState(signals::S1FloatStateValue newS1FloatState)
Modifies this configuration's S1FloatState parameter and returns itself for method-chaining and easie...
Definition Configs.hpp:5382
Configs that affect the external feedback sensor of this motor controller.
Definition Configs.hpp:2005
constexpr ExternalFeedbackConfigs & WithSensorPhase(signals::SensorPhaseValue newSensorPhase)
Modifies this configuration's SensorPhase parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:2420
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:2028
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:2694
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:2205
units::time::second_t VelocityFilterTimeConstant
The configurable time constant of the Kalman velocity filter.
Definition Configs.hpp:2070
constexpr ExternalFeedbackConfigs & WithVelocityFilterTimeConstant(units::time::second_t newVelocityFilterTimeConstant)
Modifies this configuration's VelocityFilterTimeConstant parameter and returns itself for method-chai...
Definition Configs.hpp:2307
ExternalFeedbackConfigs & WithSyncCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Sync CANdi 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:2134
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:2045
ExternalFeedbackConfigs & WithFusedCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Fused CANdi PWM 2 by passing in the CANdi objec...
ExternalFeedbackConfigs & WithRemoteCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Remote CANdi PWM 1 by passing in the CANdi obje...
constexpr ExternalFeedbackConfigs & WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for method-chai...
Definition Configs.hpp:2453
ExternalFeedbackConfigs & WithFusedCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Fused CANdi PWM 1 by passing in the CANdi objec...
constexpr ExternalFeedbackConfigs & WithFeedbackRemoteSensorID(int newFeedbackRemoteSensorID)
Modifies this configuration's FeedbackRemoteSensorID parameter and returns itself for method-chaining...
Definition Configs.hpp:2281
ExternalFeedbackConfigs & WithFusedCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Fused CANdi Quadrature by passing in the CANdi ...
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:2393
constexpr ExternalFeedbackConfigs & WithRotorToSensorRatio(units::dimensionless::scalar_t newRotorToSensorRatio)
Modifies this configuration's RotorToSensorRatio parameter and returns itself for method-chaining and...
Definition Configs.hpp:2260
ExternalFeedbackConfigs & WithSyncCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Sync CANdi PWM 2 by passing in the CANdi object...
std::string ToString() const override
Definition Configs.hpp:2662
signals::SensorPhaseValue SensorPhase
The relationship between the motor controlled by a Talon and the external sensor connected to the dat...
Definition Configs.hpp:2150
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:2084
ExternalFeedbackConfigs & WithRemoteCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Remote CANdi Quadrature by passing in the CANdi...
int FeedbackRemoteSensorID
Device ID of which remote device to use.
Definition Configs.hpp:2055
constexpr ExternalFeedbackConfigs & WithSensorToMechanismRatio(units::dimensionless::scalar_t newSensorToMechanismRatio)
Modifies this configuration's SensorToMechanismRatio parameter and returns itself for method-chaining...
Definition Configs.hpp:2232
constexpr ExternalFeedbackConfigs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:2497
std::string Serialize() const override
Definition Configs.hpp:2678
ExternalFeedbackConfigs & WithRemoteCANdiPwm2(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Remote CANdi PWM 2 by passing in the CANdi obje...
int QuadratureEdgesPerRotation
The number of quadrature edges in one rotation for the quadrature sensor connected to the Talon data ...
Definition Configs.hpp:2172
constexpr ExternalFeedbackConfigs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:2332
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 Sync CANdi PWM 2 by passing in the CANdi object...
FeedbackConfigs & WithFusedCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Fused CANdi PWM 1 by passing in the CANdi objec...
std::string ToString() const override
Definition Configs.hpp:1946
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 Remote CANdi PWM 2 by passing in the CANdi obje...
FeedbackConfigs & WithRemoteCANdiQuadrature(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Remote CANdi Quadrature by passing in the CANdi...
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:1972
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:1959
FeedbackConfigs & WithRemoteCANdiPwm1(const hardware::core::CoreCANdi &device)
Helper method to configure this feedback group to use Remote CANdi PWM 1 by passing in the CANdi obje...
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 Fused CANdi Quadrature by passing in the CANdi ...
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 Sync CANdi 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 Fused CANdi PWM 2 by passing in the CANdi objec...
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:4993
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:5122
std::string ToString() const override
Definition Configs.hpp:5156
units::angle::degree_t FOVCenterY
Specifies the target center of the Field of View in the Y direction.
Definition Configs.hpp:5022
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:5148
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5178
units::angle::degree_t FOVRangeX
Specifies the target range of the Field of View in the X direction.
Definition Configs.hpp:5037
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:5072
std::string Serialize() const override
Definition Configs.hpp:5167
units::angle::degree_t FOVCenterX
Specifies the target center of the Field of View in the X direction.
Definition Configs.hpp:5009
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:5096
units::angle::degree_t FOVRangeY
Specifies the target range of the Field of View in the Y direction.
Definition Configs.hpp:5052
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:3415
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:3920
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:3424
constexpr HardwareLimitSwitchConfigs & WithForwardLimitAutosetPositionValue(units::angle::turn_t newForwardLimitAutosetPositionValue)
Modifies this configuration's ForwardLimitAutosetPositionValue parameter and returns itself for metho...
Definition Configs.hpp:3596
units::angle::turn_t ForwardLimitAutosetPositionValue
The value to automatically set the position to when the forward limit switch is asserted.
Definition Configs.hpp:3443
signals::ForwardLimitSourceValue ForwardLimitSource
Determines where to poll the forward limit switch.
Definition Configs.hpp:3470
constexpr HardwareLimitSwitchConfigs & WithForwardLimitEnable(bool newForwardLimitEnable)
Modifies this configuration's ForwardLimitEnable parameter and returns itself for method-chaining and...
Definition Configs.hpp:3614
bool ForwardLimitEnable
If enabled, motor output is set to neutral when the forward limit switch is asserted and positive out...
Definition Configs.hpp:3450
bool ReverseLimitAutosetPositionEnable
If enabled, the position is automatically set to a specific value, specified by ReverseLimitAutosetPo...
Definition Configs.hpp:3494
bool ForwardLimitAutosetPositionEnable
If enabled, the position is automatically set to a specific value, specified by ForwardLimitAutosetPo...
Definition Configs.hpp:3432
constexpr HardwareLimitSwitchConfigs & WithReverseLimitAutosetPositionValue(units::angle::turn_t newReverseLimitAutosetPositionValue)
Modifies this configuration's ReverseLimitAutosetPositionValue parameter and returns itself for metho...
Definition Configs.hpp:3723
constexpr HardwareLimitSwitchConfigs & WithReverseLimitSource(signals::ReverseLimitSourceValue newReverseLimitSource)
Modifies this configuration's ReverseLimitSource parameter and returns itself for method-chaining and...
Definition Configs.hpp:3771
signals::ReverseLimitTypeValue ReverseLimitType
Determines if the reverse limit switch is normally-open (default) or normally-closed.
Definition Configs.hpp:3486
units::angle::turn_t ReverseLimitAutosetPositionValue
The value to automatically set the position to when the reverse limit switch is asserted.
Definition Configs.hpp:3505
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:3574
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3958
constexpr HardwareLimitSwitchConfigs & WithForwardLimitRemoteSensorID(int newForwardLimitRemoteSensorID)
Modifies this configuration's ForwardLimitRemoteSensorID parameter and returns itself for method-chai...
Definition Configs.hpp:3665
constexpr HardwareLimitSwitchConfigs & WithReverseLimitAutosetPositionEnable(bool newReverseLimitAutosetPositionEnable)
Modifies this configuration's ReverseLimitAutosetPositionEnable parameter and returns itself for meth...
Definition Configs.hpp:3701
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:3682
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:3741
int ForwardLimitRemoteSensorID
Device ID of the remote device if using remote limit switch features for the forward limit switch.
Definition Configs.hpp:3480
constexpr HardwareLimitSwitchConfigs & WithForwardLimitType(signals::ForwardLimitTypeValue newForwardLimitType)
Modifies this configuration's ForwardLimitType parameter and returns itself for method-chaining and e...
Definition Configs.hpp:3555
signals::ReverseLimitSourceValue ReverseLimitSource
Determines where to poll the reverse limit switch.
Definition Configs.hpp:3532
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:3939
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:3792
constexpr HardwareLimitSwitchConfigs & WithForwardLimitSource(signals::ForwardLimitSourceValue newForwardLimitSource)
Modifies this configuration's ForwardLimitSource parameter and returns itself for method-chaining and...
Definition Configs.hpp:3644
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:3512
int ReverseLimitRemoteSensorID
Device ID of the remote device if using remote limit switch features for the reverse limit switch.
Definition Configs.hpp:3542
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:4288
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:4362
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:4406
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:4347
std::string Serialize() const override
Definition Configs.hpp:4502
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:4384
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:4317
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:4432
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:4306
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:4332
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4514
std::string ToString() const override
Definition Configs.hpp:4490
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:4482
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:4457
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:3053
constexpr OpenLoopRampsConfigs & WithVoltageOpenLoopRampPeriod(units::time::second_t newVoltageOpenLoopRampPeriod)
Modifies this configuration's VoltageOpenLoopRampPeriod parameter and returns itself for method-chain...
Definition Configs.hpp:3143
std::string Serialize() const override
Definition Configs.hpp:3185
constexpr OpenLoopRampsConfigs & WithDutyCycleOpenLoopRampPeriod(units::time::second_t newDutyCycleOpenLoopRampPeriod)
Modifies this configuration's DutyCycleOpenLoopRampPeriod parameter and returns itself for method-cha...
Definition Configs.hpp:3118
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:3084
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:3097
std::string ToString() const override
Definition Configs.hpp:3175
constexpr OpenLoopRampsConfigs & WithTorqueOpenLoopRampPeriod(units::time::second_t newTorqueOpenLoopRampPeriod)
Modifies this configuration's TorqueOpenLoopRampPeriod parameter and returns itself for method-chaini...
Definition Configs.hpp:3167
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:3070
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:3195
Configs related to CANdi's PWM interface on the Signal 1 input (S1IN)
Definition Configs.hpp:5617
constexpr PWM1Configs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5755
units::angle::turn_t AbsoluteSensorOffset
The offset applied to the PWM sensor.
Definition Configs.hpp:5632
constexpr PWM1Configs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:5692
bool SensorDirection
Direction of the PWM sensor to determine positive rotation.
Definition Configs.hpp:5673
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5783
std::string ToString() const override
Definition Configs.hpp:5763
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:5665
constexpr PWM1Configs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:5736
std::string Serialize() const override
Definition Configs.hpp:5773
Configs related to CANdi's PWM interface on the Signal 2 input (S2IN)
Definition Configs.hpp:5808
units::angle::turn_t AbsoluteSensorOffset
The offset applied to the PWM sensor.
Definition Configs.hpp:5823
std::string Serialize() const override
Definition Configs.hpp:5964
constexpr PWM2Configs & WithAbsoluteSensorDiscontinuityPoint(units::angle::turn_t newAbsoluteSensorDiscontinuityPoint)
Modifies this configuration's AbsoluteSensorDiscontinuityPoint parameter and returns itself for metho...
Definition Configs.hpp:5927
units::angle::turn_t AbsoluteSensorDiscontinuityPoint
The positive discontinuity point of the absolute sensor in rotations.
Definition Configs.hpp:5856
constexpr PWM2Configs & WithAbsoluteSensorOffset(units::angle::turn_t newAbsoluteSensorOffset)
Modifies this configuration's AbsoluteSensorOffset parameter and returns itself for method-chaining a...
Definition Configs.hpp:5883
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5974
std::string ToString() const override
Definition Configs.hpp:5954
constexpr PWM2Configs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5946
bool SensorDirection
Direction of the PWM sensor to determine positive rotation.
Definition Configs.hpp:5864
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:4825
units::dimensionless::scalar_t MinSignalStrengthForValidMeasurement
The minimum allowable signal strength before determining the measurement is valid.
Definition Configs.hpp:4870
std::string ToString() const override
Definition Configs.hpp:4949
constexpr ProximityParamsConfigs & WithProximityThreshold(units::length::meter_t newProximityThreshold)
Modifies this configuration's ProximityThreshold parameter and returns itself for method-chaining and...
Definition Configs.hpp:4886
constexpr ProximityParamsConfigs & WithMinSignalStrengthForValidMeasurement(units::dimensionless::scalar_t newMinSignalStrengthForValidMeasurement)
Modifies this configuration's MinSignalStrengthForValidMeasurement parameter and returns itself for m...
Definition Configs.hpp:4941
std::string Serialize() const override
Definition Configs.hpp:4959
units::length::meter_t ProximityThreshold
Threshold for object detection.
Definition Configs.hpp:4837
constexpr ProximityParamsConfigs & WithProximityHysteresis(units::length::meter_t newProximityHysteresis)
Modifies this configuration's ProximityHysteresis parameter and returns itself for method-chaining an...
Definition Configs.hpp:4914
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4969
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:4854
Configs related to CANdi's quadrature interface using both the S1IN and S2IN inputs.
Definition Configs.hpp:5490
int QuadratureEdgesPerRotation
The number of quadrature edges in one rotation for the quadrature sensor connected to the Talon data ...
Definition Configs.hpp:5515
std::string ToString() const override
Definition Configs.hpp:5579
constexpr QuadratureConfigs & WithSensorDirection(bool newSensorDirection)
Modifies this configuration's SensorDirection parameter and returns itself for method-chaining and ea...
Definition Configs.hpp:5571
std::string Serialize() const override
Definition Configs.hpp:5588
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:5597
bool SensorDirection
Direction of the quadrature sensor to determine positive rotation.
Definition Configs.hpp:5523
constexpr QuadratureConfigs & WithQuadratureEdgesPerRotation(int newQuadratureEdgesPerRotation)
Modifies this configuration's QuadratureEdgesPerRotation parameter and returns itself for method-chai...
Definition Configs.hpp:5552
Gains for the specified slot.
Definition Configs.hpp:5997
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:6075
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:6211
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:6108
static Slot0Configs From(const SlotConfigs &value)
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:6159
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:6329
std::string ToString() const override
Definition Configs.hpp:6421
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:6141
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:6274
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:6016
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:6182
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:6301
constexpr Slot0Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:6413
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:6453
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:6354
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:6053
constexpr Slot0Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:6384
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:6091
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:6241
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:6122
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:6034
std::string Serialize() const override
Definition Configs.hpp:6437
Gains for the specified slot.
Definition Configs.hpp:6492
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:6511
std::string Serialize() const override
Definition Configs.hpp:6932
static Slot1Configs From(const SlotConfigs &value)
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:6617
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:6706
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:6769
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:6603
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:6570
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:6548
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:6529
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:6654
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:6586
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:6677
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:6849
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:6796
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:6736
constexpr Slot1Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:6908
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:6824
std::string ToString() const override
Definition Configs.hpp:6916
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:6636
constexpr Slot1Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:6879
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:6948
Gains for the specified slot.
Definition Configs.hpp:6987
std::string Serialize() const override
Definition Configs.hpp:7427
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:7344
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:7231
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:7264
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:7098
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:7131
constexpr Slot2Configs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:7374
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:7443
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:7201
constexpr Slot2Configs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:7403
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:7065
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:7172
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:7081
static Slot2Configs From(const SlotConfigs &value)
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:7043
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:7291
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:7006
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:7149
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:7024
std::string ToString() const override
Definition Configs.hpp:7411
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:7319
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:7112
Gains for the specified slot.
Definition Configs.hpp:7481
static SlotConfigs From(const Slot2Configs &value)
std::string ToString() const
Definition Configs.hpp:7965
constexpr SlotConfigs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition Configs.hpp:7920
static SlotConfigs From(const Slot1Configs &value)
units::dimensionless::scalar_t kI
Integral Gain.
Definition Configs.hpp:7570
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:7810
constexpr SlotConfigs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition Configs.hpp:7949
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize)
Definition Configs.hpp:7998
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:7777
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static Feedforward Sign during position closed loop.
Definition Configs.hpp:7695
units::dimensionless::scalar_t kV
Velocity Feedforward Gain.
Definition Configs.hpp:7627
units::dimensionless::scalar_t kS
Static Feedforward Gain.
Definition Configs.hpp:7611
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:7837
units::dimensionless::scalar_t kP
Proportional Gain.
Definition Configs.hpp:7552
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:7865
int SlotNumber
Chooses which slot these configs are for.
Definition Configs.hpp:7959
units::dimensionless::scalar_t kD
Derivative Gain.
Definition Configs.hpp:7589
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:7718
units::dimensionless::scalar_t kA
Acceleration Feedforward Gain.
Definition Configs.hpp:7644
std::string Serialize() const
Definition Configs.hpp:7981
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:7747
signals::GravityTypeValue GravityType
Gravity Feedforward/Feedback Type.
Definition Configs.hpp:7677
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:7890
units::dimensionless::scalar_t kG
Gravity Feedforward/Feedback Gain.
Definition Configs.hpp:7658
Configs that affect how software-limit switches behave.
Definition Configs.hpp:4123
units::angle::turn_t ReverseSoftLimitThreshold
Position threshold for reverse soft limit features.
Definition Configs.hpp:4160
std::string ToString() const override
Definition Configs.hpp:4242
constexpr SoftwareLimitSwitchConfigs & WithForwardSoftLimitThreshold(units::angle::turn_t newForwardSoftLimitThreshold)
Modifies this configuration's ForwardSoftLimitThreshold parameter and returns itself for method-chain...
Definition Configs.hpp:4213
units::angle::turn_t ForwardSoftLimitThreshold
Position threshold for forward soft limit features.
Definition Configs.hpp:4150
constexpr SoftwareLimitSwitchConfigs & WithReverseSoftLimitThreshold(units::angle::turn_t newReverseSoftLimitThreshold)
Modifies this configuration's ReverseSoftLimitThreshold parameter and returns itself for method-chain...
Definition Configs.hpp:4234
constexpr SoftwareLimitSwitchConfigs & WithReverseSoftLimitEnable(bool newReverseSoftLimitEnable)
Modifies this configuration's ReverseSoftLimitEnable parameter and returns itself for method-chaining...
Definition Configs.hpp:4192
std::string Serialize() const override
Definition Configs.hpp:4253
bool ReverseSoftLimitEnable
If enabled, the motor output is set to neutral if position exceeds ReverseSoftLimitThreshold and reve...
Definition Configs.hpp:4140
constexpr SoftwareLimitSwitchConfigs & WithForwardSoftLimitEnable(bool newForwardSoftLimitEnable)
Modifies this configuration's ForwardSoftLimitEnable parameter and returns itself for method-chaining...
Definition Configs.hpp:4174
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4264
bool ForwardSoftLimitEnable
If enabled, the motor output is set to neutral if position exceeds ForwardSoftLimitThreshold and forw...
Definition Configs.hpp:4133
Configs that affect the ToF sensor.
Definition Configs.hpp:4724
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:4779
std::string Serialize() const override
Definition Configs.hpp:4796
signals::UpdateModeValue UpdateMode
Update mode of the CANrange.
Definition Configs.hpp:4733
constexpr ToFParamsConfigs & WithUpdateMode(signals::UpdateModeValue newUpdateMode)
Modifies this configuration's UpdateMode parameter and returns itself for method-chaining and easier ...
Definition Configs.hpp:4757
units::frequency::hertz_t UpdateFrequency
Rate at which the CANrange will take measurements.
Definition Configs.hpp:4744
std::string ToString() const override
Definition Configs.hpp:4787
ctre::phoenix::StatusCode Deserialize(const std::string &to_deserialize) override
Definition Configs.hpp:4805
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 CANdi, a CAN digital input device that detects when a digital signal is asserted or deasser...
Definition CoreCANdi.hpp:911
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:3760
static constexpr int Disabled
Talon will utilize hall sensors without advanced features.
Definition SpnEnums.hpp:3767
If a brushed motor is selected with Motor Arrangement, this config determines which of three leads to...
Definition SpnEnums.hpp:4901
int value
Definition SpnEnums.hpp:4903
static constexpr int Leads_A_and_B
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:4916
Choose what sensor source is used for differential control of a mechanism.
Definition SpnEnums.hpp:3236
static constexpr int Disabled
Disable differential control.
Definition SpnEnums.hpp:3243
Choose what sensor source is reported via API and used by closed-loop and limit features.
Definition SpnEnums.hpp:4388
static constexpr int Commutation
Use the external sensor used for motor commutation.
Definition SpnEnums.hpp:4395
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:3849
int value
Definition SpnEnums.hpp:3851
static constexpr int Disabled
Motor is not selected.
Definition SpnEnums.hpp:3858
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:2911
int value
Definition SpnEnums.hpp:2913
static constexpr int LimitSwitchPin
Use the reverse limit switch pin on the limit switch connector.
Definition SpnEnums.hpp:2918
Determines if the reverse limit switch is normally-open (default) or normally-closed.
Definition SpnEnums.hpp:2824
static constexpr int NormallyOpen
Definition SpnEnums.hpp:2828
int value
Definition SpnEnums.hpp:2826
What value the Signal 1 input (S1IN) needs to be for the CANdi to detect as Closed.
Definition SpnEnums.hpp:4698
int value
Definition SpnEnums.hpp:4700
static constexpr int CloseWhenNotFloating
The S1 input will be treated as closed when it is not floating.
Definition SpnEnums.hpp:4705
The floating state of the Signal 1 input (S1IN).
Definition SpnEnums.hpp:4158
int value
Definition SpnEnums.hpp:4160
static constexpr int FloatDetect
The input will attempt to detect when it is floating.
Definition SpnEnums.hpp:4166
What value the Signal 2 input (S2IN) needs to be for the CANdi to detect as Closed.
Definition SpnEnums.hpp:4801
int value
Definition SpnEnums.hpp:4803
static constexpr int CloseWhenNotFloating
The S2 input will be treated as closed when it is not floating.
Definition SpnEnums.hpp:4808
The floating state of the Signal 2 input (S2IN).
Definition SpnEnums.hpp:4251
int value
Definition SpnEnums.hpp:4253
static constexpr int FloatDetect
The input will attempt to detect when it is floating.
Definition SpnEnums.hpp:4259
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:4615
int value
Definition SpnEnums.hpp:4617
static constexpr int Aligned
The sensor direction is normally aligned with the motor.
Definition SpnEnums.hpp:4622
Static Feedforward Sign during position closed loop.
Definition SpnEnums.hpp:3366
static constexpr int UseVelocitySign
Use the velocity reference sign.
Definition SpnEnums.hpp:3375
Update mode of the CANrange.
Definition SpnEnums.hpp:3670
int value
Definition SpnEnums.hpp:3672
static constexpr int ShortRange100Hz
Updates distance/proximity at 100hz using short-range detection mode.
Definition SpnEnums.hpp:3677
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18