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