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