CTRE Phoenix 6 C++ 26.3.0
Loading...
Searching...
No Matches
SlotConfigs.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
13#include <unordered_map>
14
15namespace ctre {
16namespace phoenix6 {
17
18
19namespace configs {
20/**
21 * \brief Gains for the specified slot.
22 *
23 * \details If this slot is selected, these gains are used in closed
24 * loop control requests.
25 */
27 struct SlotSpns {
28 int kPSpn;
29 int kISpn;
30 int kDSpn;
31 int kSSpn;
32 int kVSpn;
33 int kASpn;
34 int kGSpn;
35 int GravityTypeSpn;
36 int StaticFeedforwardSignSpn;
37 int GravityArmPositionOffsetSpn;
38 int GainSchedBehaviorSpn;
39 };
40
41 static std::unordered_map<int, SlotSpns> const genericMap;
42
43public:
44 constexpr SlotConfigs() = default;
45
46 /**
47 * \brief Proportional gain.
48 *
49 * \details The units for this gain is dependent on the control mode.
50 * Since this gain is multiplied by error in the input, the units
51 * should be defined as units of output per unit of input error. For
52 * example, when controlling velocity using a duty cycle closed loop,
53 * the units for the proportional gain will be duty cycle per rps of
54 * error, or 1/rps.
55 *
56 * - Minimum Value: 0
57 * - Maximum Value: 3.4e+38
58 * - Default Value: 0
59 * - Units:
60 */
61 units::dimensionless::scalar_t kP = 0;
62 /**
63 * \brief Integral gain.
64 *
65 * \details The units for this gain is dependent on the control mode.
66 * Since this gain is multiplied by error in the input integrated over
67 * time (in units of seconds), the units should be defined as units of
68 * output per unit of integrated input error. For example, when
69 * controlling velocity using a duty cycle closed loop, integrating
70 * velocity over time results in rps * s = rotations. Therefore, the
71 * units for the integral gain will be duty cycle per rotation of
72 * accumulated error, or 1/rot.
73 *
74 * - Minimum Value: 0
75 * - Maximum Value: 3.4e+38
76 * - Default Value: 0
77 * - Units:
78 */
79 units::dimensionless::scalar_t kI = 0;
80 /**
81 * \brief Derivative gain.
82 *
83 * \details The units for this gain is dependent on the control mode.
84 * Since this gain is multiplied by the derivative of error in the
85 * input with respect to time (in units of seconds), the units should
86 * be defined as units of output per unit of the differentiated input
87 * error. For example, when controlling velocity using a duty cycle
88 * closed loop, the derivative of velocity with respect to time is rot
89 * per sec², which is acceleration. Therefore, the units for the
90 * derivative gain will be duty cycle per unit of acceleration error,
91 * or 1/(rot per sec²).
92 *
93 * - Minimum Value: 0
94 * - Maximum Value: 3.4e+38
95 * - Default Value: 0
96 * - Units:
97 */
98 units::dimensionless::scalar_t kD = 0;
99 /**
100 * \brief Static feedforward gain.
101 *
102 * \details This is added to the closed loop output. The unit for this
103 * constant is dependent on the control mode, typically fractional
104 * duty cycle, voltage, or torque current.
105 *
106 * The sign is typically determined by reference velocity when using
107 * position, velocity, and Motion Magic® closed loop modes. However,
108 * when using position closed loop with zero velocity reference (no
109 * motion profiling), the application can instead use the position
110 * closed loop error by setting the Static Feedforward Sign
111 * configuration parameter. When doing so, we recommend the minimal
112 * amount of kS, otherwise the motor output may dither when closed
113 * loop error is near zero.
114 *
115 * - Minimum Value: -128
116 * - Maximum Value: 127
117 * - Default Value: 0
118 * - Units:
119 */
120 units::dimensionless::scalar_t kS = 0;
121 /**
122 * \brief Velocity feedforward gain.
123 *
124 * \details The units for this gain is dependent on the control mode.
125 * Since this gain is multiplied by the requested velocity, the units
126 * should be defined as units of output per unit of requested input
127 * velocity. For example, when controlling velocity using a duty cycle
128 * closed loop, the units for the velocity feedfoward gain will be
129 * duty cycle per requested rps, or 1/rps.
130 *
131 * - Minimum Value: 0
132 * - Maximum Value: 3.4e+38
133 * - Default Value: 0
134 * - Units:
135 */
136 units::dimensionless::scalar_t kV = 0;
137 /**
138 * \brief Acceleration feedforward gain.
139 *
140 * \details The units for this gain is dependent on the control mode.
141 * Since this gain is multiplied by the requested acceleration, the
142 * units should be defined as units of output per unit of requested
143 * input acceleration. For example, when controlling velocity using a
144 * duty cycle closed loop, the units for the acceleration feedfoward
145 * gain will be duty cycle per requested rot per sec², or 1/(rot per
146 * sec²).
147 *
148 * - Minimum Value: 0
149 * - Maximum Value: 3.4e+38
150 * - Default Value: 0
151 * - Units:
152 */
153 units::dimensionless::scalar_t kA = 0;
154 /**
155 * \brief Gravity feedforward/feedback gain. The type of gravity
156 * compensation is selected by #GravityType.
157 *
158 * \details This is added to the closed loop output. The sign is
159 * determined by the gravity type. The unit for this constant is
160 * dependent on the control mode, typically fractional duty cycle,
161 * voltage, or torque current.
162 *
163 * Note that kG may be negative for some counterbalanced mechanisms.
164 *
165 * - Minimum Value: -128
166 * - Maximum Value: 127
167 * - Default Value: 0
168 * - Units:
169 */
170 units::dimensionless::scalar_t kG = 0;
171 /**
172 * \brief Gravity feedforward/feedback type.
173 *
174 * This determines the type of the gravity feedforward/feedback.
175 *
176 * Choose Elevator_Static for systems where the gravity feedforward is
177 * constant, such as an elevator. The gravity feedforward output will
178 * always have the same sign.
179 *
180 * Choose Arm_Cosine for systems where the gravity feedback is
181 * dependent on the angular position of the mechanism, such as an arm.
182 * The gravity feedback output will vary depending on the mechanism
183 * angular position. Note that the sensor offset and ratios must be
184 * configured so that the sensor reports a position of 0 when the
185 * mechanism is horizonal (parallel to the ground), and the reported
186 * sensor position is 1:1 with the mechanism.
187 *
188 */
190 /**
191 * \brief Static feedforward sign during position closed loop.
192 *
193 * This determines the sign of the applied kS during position
194 * closed-loop modes. The default behavior uses the velocity reference
195 * sign. This works well with velocity closed loop, Motion Magic®
196 * controls, and position closed loop when velocity reference is
197 * specified (motion profiling).
198 *
199 * However, when using position closed loop with zero velocity
200 * reference (no motion profiling), the application may want to apply
201 * static feedforward based on the sign of closed loop error instead.
202 * When doing so, we recommend using the minimal amount of kS,
203 * otherwise the motor output may dither when closed loop error is
204 * near zero.
205 *
206 */
208 /**
209 * \brief Gravity feedback position offset when using the Arm/Cosine
210 * gravity type.
211 *
212 * This is an offset applied to the position of the arm, within
213 * (-0.25, 0.25) rot, before calculating the output of kG. This is
214 * useful when the center of gravity of the arm is offset from the
215 * actual zero point of the arm, such as when the arm and intake form
216 * an L shape.
217 *
218 * - Minimum Value: -0.25
219 * - Maximum Value: 0.25
220 * - Default Value: 0
221 * - Units: rotations
222 */
223 units::angle::turn_t GravityArmPositionOffset = 0_tr;
224 /**
225 * \brief The behavior of the gain scheduler on this slot. This
226 * specifies which gains to use while within the configured
227 * GainSchedErrorThreshold. The default is to continue using the
228 * specified slot.
229 *
230 * \details Gain scheduling will not take effect when running velocity
231 * closed-loop controls.
232 *
233 */
235
236 /**
237 * \brief Modifies this configuration's kP parameter and returns itself for
238 * method-chaining and easier to use config API.
239 *
240 * Proportional gain.
241 *
242 * \details The units for this gain is dependent on the control mode.
243 * Since this gain is multiplied by error in the input, the units
244 * should be defined as units of output per unit of input error. For
245 * example, when controlling velocity using a duty cycle closed loop,
246 * the units for the proportional gain will be duty cycle per rps of
247 * error, or 1/rps.
248 *
249 * - Minimum Value: 0
250 * - Maximum Value: 3.4e+38
251 * - Default Value: 0
252 * - Units:
253 *
254 * \param newKP Parameter to modify
255 * \returns Itself
256 */
257 constexpr SlotConfigs &WithKP(units::dimensionless::scalar_t newKP)
258 {
259 kP = std::move(newKP);
260 return *this;
261 }
262
263 /**
264 * \brief Modifies this configuration's kI parameter and returns itself for
265 * method-chaining and easier to use config API.
266 *
267 * Integral gain.
268 *
269 * \details The units for this gain is dependent on the control mode.
270 * Since this gain is multiplied by error in the input integrated over
271 * time (in units of seconds), the units should be defined as units of
272 * output per unit of integrated input error. For example, when
273 * controlling velocity using a duty cycle closed loop, integrating
274 * velocity over time results in rps * s = rotations. Therefore, the
275 * units for the integral gain will be duty cycle per rotation of
276 * accumulated error, or 1/rot.
277 *
278 * - Minimum Value: 0
279 * - Maximum Value: 3.4e+38
280 * - Default Value: 0
281 * - Units:
282 *
283 * \param newKI Parameter to modify
284 * \returns Itself
285 */
286 constexpr SlotConfigs &WithKI(units::dimensionless::scalar_t newKI)
287 {
288 kI = std::move(newKI);
289 return *this;
290 }
291
292 /**
293 * \brief Modifies this configuration's kD parameter and returns itself for
294 * method-chaining and easier to use config API.
295 *
296 * Derivative gain.
297 *
298 * \details The units for this gain is dependent on the control mode.
299 * Since this gain is multiplied by the derivative of error in the
300 * input with respect to time (in units of seconds), the units should
301 * be defined as units of output per unit of the differentiated input
302 * error. For example, when controlling velocity using a duty cycle
303 * closed loop, the derivative of velocity with respect to time is rot
304 * per sec², which is acceleration. Therefore, the units for the
305 * derivative gain will be duty cycle per unit of acceleration error,
306 * or 1/(rot per sec²).
307 *
308 * - Minimum Value: 0
309 * - Maximum Value: 3.4e+38
310 * - Default Value: 0
311 * - Units:
312 *
313 * \param newKD Parameter to modify
314 * \returns Itself
315 */
316 constexpr SlotConfigs &WithKD(units::dimensionless::scalar_t newKD)
317 {
318 kD = std::move(newKD);
319 return *this;
320 }
321
322 /**
323 * \brief Modifies this configuration's kS parameter and returns itself for
324 * method-chaining and easier to use config API.
325 *
326 * Static feedforward gain.
327 *
328 * \details This is added to the closed loop output. The unit for this
329 * constant is dependent on the control mode, typically fractional
330 * duty cycle, voltage, or torque current.
331 *
332 * The sign is typically determined by reference velocity when using
333 * position, velocity, and Motion Magic® closed loop modes. However,
334 * when using position closed loop with zero velocity reference (no
335 * motion profiling), the application can instead use the position
336 * closed loop error by setting the Static Feedforward Sign
337 * configuration parameter. When doing so, we recommend the minimal
338 * amount of kS, otherwise the motor output may dither when closed
339 * loop error is near zero.
340 *
341 * - Minimum Value: -128
342 * - Maximum Value: 127
343 * - Default Value: 0
344 * - Units:
345 *
346 * \param newKS Parameter to modify
347 * \returns Itself
348 */
349 constexpr SlotConfigs &WithKS(units::dimensionless::scalar_t newKS)
350 {
351 kS = std::move(newKS);
352 return *this;
353 }
354
355 /**
356 * \brief Modifies this configuration's kV parameter and returns itself for
357 * method-chaining and easier to use config API.
358 *
359 * Velocity feedforward gain.
360 *
361 * \details The units for this gain is dependent on the control mode.
362 * Since this gain is multiplied by the requested velocity, the units
363 * should be defined as units of output per unit of requested input
364 * velocity. For example, when controlling velocity using a duty cycle
365 * closed loop, the units for the velocity feedfoward gain will be
366 * duty cycle per requested rps, or 1/rps.
367 *
368 * - Minimum Value: 0
369 * - Maximum Value: 3.4e+38
370 * - Default Value: 0
371 * - Units:
372 *
373 * \param newKV Parameter to modify
374 * \returns Itself
375 */
376 constexpr SlotConfigs &WithKV(units::dimensionless::scalar_t newKV)
377 {
378 kV = std::move(newKV);
379 return *this;
380 }
381
382 /**
383 * \brief Modifies this configuration's kA parameter and returns itself for
384 * method-chaining and easier to use config API.
385 *
386 * Acceleration feedforward gain.
387 *
388 * \details The units for this gain is dependent on the control mode.
389 * Since this gain is multiplied by the requested acceleration, the
390 * units should be defined as units of output per unit of requested
391 * input acceleration. For example, when controlling velocity using a
392 * duty cycle closed loop, the units for the acceleration feedfoward
393 * gain will be duty cycle per requested rot per sec², or 1/(rot per
394 * sec²).
395 *
396 * - Minimum Value: 0
397 * - Maximum Value: 3.4e+38
398 * - Default Value: 0
399 * - Units:
400 *
401 * \param newKA Parameter to modify
402 * \returns Itself
403 */
404 constexpr SlotConfigs &WithKA(units::dimensionless::scalar_t newKA)
405 {
406 kA = std::move(newKA);
407 return *this;
408 }
409
410 /**
411 * \brief Modifies this configuration's kG parameter and returns itself for
412 * method-chaining and easier to use config API.
413 *
414 * Gravity feedforward/feedback gain. The type of gravity compensation
415 * is selected by #GravityType.
416 *
417 * \details This is added to the closed loop output. The sign is
418 * determined by the gravity type. The unit for this constant is
419 * dependent on the control mode, typically fractional duty cycle,
420 * voltage, or torque current.
421 *
422 * Note that kG may be negative for some counterbalanced mechanisms.
423 *
424 * - Minimum Value: -128
425 * - Maximum Value: 127
426 * - Default Value: 0
427 * - Units:
428 *
429 * \param newKG Parameter to modify
430 * \returns Itself
431 */
432 constexpr SlotConfigs &WithKG(units::dimensionless::scalar_t newKG)
433 {
434 kG = std::move(newKG);
435 return *this;
436 }
437
438 /**
439 * \brief Modifies this configuration's GravityType parameter and returns itself for
440 * method-chaining and easier to use config API.
441 *
442 * Gravity feedforward/feedback type.
443 *
444 * This determines the type of the gravity feedforward/feedback.
445 *
446 * Choose Elevator_Static for systems where the gravity feedforward is
447 * constant, such as an elevator. The gravity feedforward output will
448 * always have the same sign.
449 *
450 * Choose Arm_Cosine for systems where the gravity feedback is
451 * dependent on the angular position of the mechanism, such as an arm.
452 * The gravity feedback output will vary depending on the mechanism
453 * angular position. Note that the sensor offset and ratios must be
454 * configured so that the sensor reports a position of 0 when the
455 * mechanism is horizonal (parallel to the ground), and the reported
456 * sensor position is 1:1 with the mechanism.
457 *
458 *
459 * \param newGravityType Parameter to modify
460 * \returns Itself
461 */
463 {
464 GravityType = std::move(newGravityType);
465 return *this;
466 }
467
468 /**
469 * \brief Modifies this configuration's StaticFeedforwardSign parameter and returns itself for
470 * method-chaining and easier to use config API.
471 *
472 * Static feedforward sign during position closed loop.
473 *
474 * This determines the sign of the applied kS during position
475 * closed-loop modes. The default behavior uses the velocity reference
476 * sign. This works well with velocity closed loop, Motion Magic®
477 * controls, and position closed loop when velocity reference is
478 * specified (motion profiling).
479 *
480 * However, when using position closed loop with zero velocity
481 * reference (no motion profiling), the application may want to apply
482 * static feedforward based on the sign of closed loop error instead.
483 * When doing so, we recommend using the minimal amount of kS,
484 * otherwise the motor output may dither when closed loop error is
485 * near zero.
486 *
487 *
488 * \param newStaticFeedforwardSign Parameter to modify
489 * \returns Itself
490 */
492 {
493 StaticFeedforwardSign = std::move(newStaticFeedforwardSign);
494 return *this;
495 }
496
497 /**
498 * \brief Modifies this configuration's GravityArmPositionOffset parameter and returns itself for
499 * method-chaining and easier to use config API.
500 *
501 * Gravity feedback position offset when using the Arm/Cosine gravity
502 * type.
503 *
504 * This is an offset applied to the position of the arm, within
505 * (-0.25, 0.25) rot, before calculating the output of kG. This is
506 * useful when the center of gravity of the arm is offset from the
507 * actual zero point of the arm, such as when the arm and intake form
508 * an L shape.
509 *
510 * - Minimum Value: -0.25
511 * - Maximum Value: 0.25
512 * - Default Value: 0
513 * - Units: rotations
514 *
515 * \param newGravityArmPositionOffset Parameter to modify
516 * \returns Itself
517 */
518 constexpr SlotConfigs &WithGravityArmPositionOffset(units::angle::turn_t newGravityArmPositionOffset)
519 {
520 GravityArmPositionOffset = std::move(newGravityArmPositionOffset);
521 return *this;
522 }
523
524 /**
525 * \brief Modifies this configuration's GainSchedBehavior parameter and returns itself for
526 * method-chaining and easier to use config API.
527 *
528 * The behavior of the gain scheduler on this slot. This specifies
529 * which gains to use while within the configured
530 * GainSchedErrorThreshold. The default is to continue using the
531 * specified slot.
532 *
533 * \details Gain scheduling will not take effect when running velocity
534 * closed-loop controls.
535 *
536 *
537 * \param newGainSchedBehavior Parameter to modify
538 * \returns Itself
539 */
541 {
542 GainSchedBehavior = std::move(newGainSchedBehavior);
543 return *this;
544 }
545
546
547 /**
548 * \brief Chooses which slot these configs are for.
549 */
550 int SlotNumber = 0;
551
552 /**
553 * Converts the provided value to an instance of this type.
554 *
555 * \param value The value to convert
556 * \returns Converted value
557 */
558 static SlotConfigs From(Slot0Configs const &value);
559 /**
560 * Converts the provided value to an instance of this type.
561 *
562 * \param value The value to convert
563 * \returns Converted value
564 */
565 static SlotConfigs From(Slot1Configs const &value);
566 /**
567 * Converts the provided value to an instance of this type.
568 *
569 * \param value The value to convert
570 * \returns Converted value
571 */
572 static SlotConfigs From(Slot2Configs const &value);
573
574 std::string ToString() const override;
575
576 std::string Serialize() const final;
577 ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final;
578};
579
580}
581}
582}
Definition Configuration.hpp:17
Gains for the specified slot.
Definition Slot0Configs.hpp:26
Gains for the specified slot.
Definition Slot1Configs.hpp:26
Gains for the specified slot.
Definition Slot2Configs.hpp:26
Gains for the specified slot.
Definition SlotConfigs.hpp:26
constexpr SlotConfigs & WithGravityType(signals::GravityTypeValue newGravityType)
Modifies this configuration's GravityType parameter and returns itself for method-chaining and easier...
Definition SlotConfigs.hpp:462
units::dimensionless::scalar_t kI
Integral gain.
Definition SlotConfigs.hpp:79
static SlotConfigs From(Slot1Configs const &value)
Converts the provided value to an instance of this type.
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 SlotConfigs.hpp:349
constexpr SlotConfigs & WithStaticFeedforwardSign(signals::StaticFeedforwardSignValue newStaticFeedforwardSign)
Modifies this configuration's StaticFeedforwardSign parameter and returns itself for method-chaining ...
Definition SlotConfigs.hpp:491
units::angle::turn_t GravityArmPositionOffset
Gravity feedback position offset when using the Arm/Cosine gravity type.
Definition SlotConfigs.hpp:223
signals::GainSchedBehaviorValue GainSchedBehavior
The behavior of the gain scheduler on this slot.
Definition SlotConfigs.hpp:234
std::string ToString() const override
static SlotConfigs From(Slot2Configs const &value)
Converts the provided value to an instance of this type.
std::string Serialize() const final
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 SlotConfigs.hpp:316
signals::StaticFeedforwardSignValue StaticFeedforwardSign
Static feedforward sign during position closed loop.
Definition SlotConfigs.hpp:207
units::dimensionless::scalar_t kV
Velocity feedforward gain.
Definition SlotConfigs.hpp:136
units::dimensionless::scalar_t kS
Static feedforward gain.
Definition SlotConfigs.hpp:120
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 SlotConfigs.hpp:376
units::dimensionless::scalar_t kP
Proportional gain.
Definition SlotConfigs.hpp:61
constexpr SlotConfigs & WithGainSchedBehavior(signals::GainSchedBehaviorValue newGainSchedBehavior)
Modifies this configuration's GainSchedBehavior parameter and returns itself for method-chaining and ...
Definition SlotConfigs.hpp:540
constexpr SlotConfigs & WithGravityArmPositionOffset(units::angle::turn_t newGravityArmPositionOffset)
Modifies this configuration's GravityArmPositionOffset parameter and returns itself for method-chaini...
Definition SlotConfigs.hpp:518
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 SlotConfigs.hpp:404
int SlotNumber
Chooses which slot these configs are for.
Definition SlotConfigs.hpp:550
units::dimensionless::scalar_t kD
Derivative gain.
Definition SlotConfigs.hpp:98
static SlotConfigs From(Slot0Configs const &value)
Converts the provided value to an instance of this type.
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 SlotConfigs.hpp:257
units::dimensionless::scalar_t kA
Acceleration feedforward gain.
Definition SlotConfigs.hpp:153
ctre::phoenix::StatusCode Deserialize(std::string const &to_deserialize) final
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 SlotConfigs.hpp:286
signals::GravityTypeValue GravityType
Gravity feedforward/feedback type.
Definition SlotConfigs.hpp:189
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 SlotConfigs.hpp:432
units::dimensionless::scalar_t kG
Gravity feedforward/feedback gain.
Definition SlotConfigs.hpp:170
Definition motor_constants.h:14
The behavior of the gain scheduler on this slot.
Definition SpnEnums.hpp:5059
static constexpr int Inactive
No gain scheduling will occur.
Definition SpnEnums.hpp:5065
Gravity feedforward/feedback type.
Definition SpnEnums.hpp:1488
static constexpr int Elevator_Static
The system's gravity feedforward is constant, such as an elevator.
Definition SpnEnums.hpp:1495
Static feedforward sign during position closed loop.
Definition SpnEnums.hpp:2475
static constexpr int UseVelocitySign
Use the velocity reference sign.
Definition SpnEnums.hpp:2483