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