CTRE Phoenix 6 C++ 25.1.0
Loading...
Searching...
No Matches
SwerveModuleConstants.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
12#include <units/length.h>
13#include <units/moment_of_inertia.h>
14#include <units/velocity.h>
15
16namespace ctre {
17namespace phoenix6 {
18namespace swerve {
19
20/**
21 * \brief Supported closed-loop output types.
22 */
24 Voltage = 0,
25 /** \brief Requires Pro */
27};
28
29/**
30 * \brief Supported motor arrangements for the drive motors.
31 */
33 /**
34 * \brief Talon FX integrated brushless motor.
35 */
37 /**
38 * \brief Third party NEO brushless motor connected to a Talon FXS over JST.
39 */
41 /**
42 * \brief Third party VORTEX brushless motor connected to a Talon FXS over JST.
43 */
45};
46
47/**
48 * \brief Supported motor arrangements for the steer motors.
49 */
51 /**
52 * \brief Talon FX integrated brushless motor.
53 */
55 /**
56 * \brief CTR Electronics MinionĀ® brushless motor connected to a Talon FXS over JST.
57 */
59 /**
60 * \brief Third party NEO brushless motor connected to a Talon FXS over JST.
61 */
63 /**
64 * \brief Third party VORTEX brushless motor connected to a Talon FXS over JST.
65 */
67 /**
68 * \brief Third party NEO550 brushless motor connected to a Talon FXS over JST.
69 */
71 /**
72 * \brief Brushed motor connected to a Talon FXS on terminals A and B.
73 */
75 /**
76 * \brief Brushed motor connected to a Talon FXS on terminals A and C.
77 */
79 /**
80 * \brief Brushed motor connected to a Talon FXS on terminals B and C.
81 */
83};
84
85/**
86 * \brief Supported feedback sensors for the steer motors.
87 */
89 /**
90 * \brief Requires Pro; Use signals#FeedbackSensorSourceValue#FusedCANcoder
91 * for the steer motor.
92 */
93 FusedCANcoder = 0,
94 /**
95 * \brief Requires Pro; Use signals#FeedbackSensorSourceValue#SyncCANcoder
96 * for the steer motor.
97 */
98 SyncCANcoder = 1,
99 /**
100 * \brief Use signals#FeedbackSensorSourceValue#RemoteCANcoder
101 * for the steer motor.
102 */
103 RemoteCANcoder = 2,
104};
105
106/**
107 * \brief All constants for a swerve module.
108 */
109template <
110 typename DriveMotorConfigsT,
111 typename SteerMotorConfigsT,
112 typename EncoderConfigsT,
113 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, DriveMotorConfigsT>>,
114 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, SteerMotorConfigsT>>,
115 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, EncoderConfigsT>>
116>
118 constexpr SwerveModuleConstants() = default;
119
120 /**
121 * \brief CAN ID of the steer motor.
122 */
124 /**
125 * \brief CAN ID of the drive motor.
126 */
128 /**
129 * \brief CAN ID of the absolute encoder used for azimuth.
130 */
131 int EncoderId = 0;
132 /**
133 * \brief Offset of the azimuth encoder.
134 */
135 units::angle::turn_t EncoderOffset = 0_tr;
136 /**
137 * \brief The location of this module's wheels relative to the physical center
138 * of the robot in meters along the X axis of the robot.
139 */
140 units::length::meter_t LocationX = 0_m;
141 /**
142 * \brief The location of this module's wheels relative to the physical center
143 * of the robot in meters along the Y axis of the robot.
144 */
145 units::length::meter_t LocationY = 0_m;
146 /**
147 * \brief True if the drive motor is inverted.
148 */
149 bool DriveMotorInverted = false;
150 /**
151 * \brief True if the steer motor is inverted from the azimuth. The azimuth
152 * should rotate counter-clockwise (as seen from the top of the robot) for a
153 * positive motor output.
154 */
155 bool SteerMotorInverted = false;
156 /**
157 * \brief True if the azimuth encoder is inverted from the azimuth. The encoder
158 * should report a positive velocity when the azimuth rotates counter-clockwise
159 * (as seen from the top of the robot).
160 */
161 bool EncoderInverted = false;
162 /**
163 * \brief Gear ratio between the drive motor and the wheel.
164 */
165 units::dimensionless::scalar_t DriveMotorGearRatio = 0;
166 /**
167 * \brief Gear ratio between the steer motor and the azimuth encoder. For
168 * example, the SDS Mk4 has a steering ratio of 12.8.
169 */
170 units::dimensionless::scalar_t SteerMotorGearRatio = 0;
171 /**
172 * \brief Coupled gear ratio between the azimuth encoder and the drive motor.
173 *
174 * For a typical swerve module, the azimuth turn motor also drives the wheel a
175 * nontrivial amount, which affects the accuracy of odometry and control. This
176 * ratio represents the number of rotations of the drive motor caused by a
177 * rotation of the azimuth.
178 */
179 units::dimensionless::scalar_t CouplingGearRatio = 0;
180 /**
181 * \brief Radius of the driving wheel in meters.
182 */
183 units::length::meter_t WheelRadius = 0_m;
184 /**
185 * \brief The steer motor closed-loop gains.
186 *
187 * The steer motor uses the control ouput type specified by
188 * SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains
189 * operate on azimuth rotations (after the gear ratio).
190 */
192 /**
193 * \brief The drive motor closed-loop gains.
194 *
195 * When using closed-loop control, the drive motor uses the control output type
196 * specified by DriveMotorClosedLoopOutput and any closed-loop
197 * SwerveModule#DriveRequestType. These gains operate on motor rotor rotations
198 * (before the gear ratio).
199 */
201 /**
202 * \brief The closed-loop output type to use for the steer motors.
203 */
205 /**
206 * \brief The closed-loop output type to use for the drive motors.
207 */
209 /**
210 * \brief The maximum amount of stator current the drive motors can apply
211 * without slippage.
212 */
213 units::current::ampere_t SlipCurrent = 120_A;
214 /**
215 * \brief When using open-loop drive control, this specifies the speed at which
216 * the robot travels when driven with 12 volts. This is used to approximate the
217 * output for a desired velocity. If using closed loop control, this value is
218 * ignored.
219 */
220 units::velocity::meters_per_second_t SpeedAt12Volts = 0_mps;
221 /**
222 * \brief Choose the motor used for the drive motor.
223 *
224 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
225 * Talon FXS, this should be set to the motor attached to the Talon FXS.
226 */
228 /**
229 * \brief Choose the motor used for the steer motor.
230 *
231 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
232 * Talon FXS, this should be set to the motor attached to the Talon FXS.
233 */
235 /**
236 * \brief Choose how the feedback sensors should be configured.
237 *
238 * If the robot does not support Pro, then this should be set to RemoteCANcoder.
239 * Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder
240 * depending on if there is a risk that the CANcoder can fail in a way to
241 * provide "good" data.
242 *
243 * If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not
244 * Pro-licensed, the device will automatically fall back to RemoteCANcoder and
245 * report a UsingProFeatureOnUnlicensedDevice status code.
246 */
248 /**
249 * \brief The initial configs used to configure the drive motor of the swerve
250 * module. The default value is the factory-default.
251 *
252 * Users may change the initial configuration as they need. Any config that's
253 * not referenced in the SwerveModuleConstants class is available to be changed.
254 *
255 * The list of configs that will be overwritten is as follows:
256 *
257 * - configs#MotorOutputConfigs#NeutralMode (Brake mode, overwritten with
258 * SwerveDrivetrain#ConfigNeutralMode)
259 * - configs#MotorOutputConfigs#Inverted
260 * (SwerveModuleConstants#DriveMotorInverted)
261 * - configs#Slot0Configs (SwerveModuleConstants#DriveMotorGains)
262 * - configs#CurrentLimitsConfigs#StatorCurrentLimit /
263 * configs#TorqueCurrentConfigs#PeakForwardTorqueCurrent /
264 * configs#TorqueCurrentConfigs#PeakReverseTorqueCurrent
265 * (SwerveModuleConstants#SlipCurrent)
266 * - configs#CurrentLimitsConfigs#StatorCurrentLimitEnable (Enabled)
267 *
268 */
269 DriveMotorConfigsT DriveMotorInitialConfigs = {};
270 /**
271 * \brief The initial configs used to configure the steer motor of the swerve
272 * module. The default value is the factory-default.
273 *
274 * Users may change the initial configuration as they need. Any config that's
275 * not referenced in the SwerveModuleConstants class is available to be changed.
276 *
277 * The list of configs that will be overwritten is as follows:
278 *
279 * - configs#MotorOutputConfigs#NeutralMode (Brake mode)
280 * - configs#MotorOutputConfigs#Inverted
281 * (SwerveModuleConstants#SteerMotorInverted)
282 * - configs#Slot0Configs (SwerveModuleConstants#SteerMotorGains)
283 * - configs#FeedbackConfigs#FeedbackRemoteSensorID
284 * (SwerveModuleConstants#EncoderId)
285 * - configs#FeedbackConfigs#FeedbackSensorSource
286 * (SwerveModuleConstants#FeedbackSource)
287 * - configs#FeedbackConfigs#RotorToSensorRatio
288 * (SwerveModuleConstants#SteerMotorGearRatio)
289 * - configs#MotionMagicConfigs#MotionMagicExpo_kV /
290 * configs#MotionMagicConfigs#MotionMagicExpo_kA (Calculated from gear ratios)
291 * - configs#ClosedLoopGeneralConfigs#ContinuousWrap (true)
292 *
293 */
294 SteerMotorConfigsT SteerMotorInitialConfigs = {};
295 /**
296 * \brief The initial configs used to configure the azimuth encoder of the
297 * swerve module. The default value is the factory-default.
298 *
299 * Users may change the initial configuration as they need. Any config that's
300 * not referenced in the SwerveModuleConstants class is available to be changed.
301 *
302 * For CANcoder, the list of configs that will be overwritten is as follows:
303 *
304 * - configs#MagnetSensorConfigs#MagnetOffset
305 * (SwerveModuleConstants#EncoderOffset)
306 * - configs#MagnetSensorConfigs#SensorDirection
307 * (SwerveModuleConstants#EncoderInverted)
308 *
309 */
310 EncoderConfigsT EncoderInitialConfigs = {};
311 /**
312 * \brief Simulated azimuthal inertia.
313 */
314 units::moment_of_inertia::kilogram_square_meter_t SteerInertia = 0.00001_kg_sq_m;
315 /**
316 * \brief Simulated drive inertia.
317 */
318 units::moment_of_inertia::kilogram_square_meter_t DriveInertia = 0.001_kg_sq_m;
319 /**
320 * \brief Simulated steer voltage required to overcome friction.
321 */
322 units::voltage::volt_t SteerFrictionVoltage = 0.25_V;
323 /**
324 * \brief Simulated drive voltage required to overcome friction.
325 */
326 units::voltage::volt_t DriveFrictionVoltage = 0.25_V;
327
328 /**
329 * \brief Modifies the SteerMotorId parameter and returns itself.
330 *
331 * CAN ID of the steer motor.
332 *
333 * \param newSteerMotorId Parameter to modify
334 * \returns this object
335 */
337 {
338 this->SteerMotorId = newSteerMotorId;
339 return *this;
340 }
341
342 /**
343 * \brief Modifies the DriveMotorId parameter and returns itself.
344 *
345 * CAN ID of the drive motor.
346 *
347 * \param newDriveMotorId Parameter to modify
348 * \returns this object
349 */
351 {
352 this->DriveMotorId = newDriveMotorId;
353 return *this;
354 }
355
356 /**
357 * \brief Modifies the EncoderId parameter and returns itself.
358 *
359 * CAN ID of the absolute encoder used for azimuth.
360 *
361 * \param newEncoderId Parameter to modify
362 * \returns this object
363 */
365 {
366 this->EncoderId = newEncoderId;
367 return *this;
368 }
369
370 /**
371 * \brief Modifies the EncoderOffset parameter and returns itself.
372 *
373 * Offset of the azimuth encoder.
374 *
375 * \param newEncoderOffset Parameter to modify
376 * \returns this object
377 */
379 {
380 this->EncoderOffset = newEncoderOffset;
381 return *this;
382 }
383
384 /**
385 * \brief Modifies the LocationX parameter and returns itself.
386 *
387 * The location of this module's wheels relative to the physical center of the
388 * robot in meters along the X axis of the robot.
389 *
390 * \param newLocationX Parameter to modify
391 * \returns this object
392 */
394 {
395 this->LocationX = newLocationX;
396 return *this;
397 }
398
399 /**
400 * \brief Modifies the LocationY parameter and returns itself.
401 *
402 * The location of this module's wheels relative to the physical center of the
403 * robot in meters along the Y axis of the robot.
404 *
405 * \param newLocationY Parameter to modify
406 * \returns this object
407 */
409 {
410 this->LocationY = newLocationY;
411 return *this;
412 }
413
414 /**
415 * \brief Modifies the DriveMotorInverted parameter and returns itself.
416 *
417 * True if the drive motor is inverted.
418 *
419 * \param newDriveMotorInverted Parameter to modify
420 * \returns this object
421 */
423 {
424 this->DriveMotorInverted = newDriveMotorInverted;
425 return *this;
426 }
427
428 /**
429 * \brief Modifies the SteerMotorInverted parameter and returns itself.
430 *
431 * True if the steer motor is inverted from the azimuth. The azimuth should
432 * rotate counter-clockwise (as seen from the top of the robot) for a positive
433 * motor output.
434 *
435 * \param newSteerMotorInverted Parameter to modify
436 * \returns this object
437 */
439 {
440 this->SteerMotorInverted = newSteerMotorInverted;
441 return *this;
442 }
443
444 /**
445 * \brief Modifies the EncoderInverted parameter and returns itself.
446 *
447 * True if the azimuth encoder is inverted from the azimuth. The encoder should
448 * report a positive velocity when the azimuth rotates counter-clockwise (as
449 * seen from the top of the robot).
450 *
451 * \param newEncoderInverted Parameter to modify
452 * \returns this object
453 */
455 {
456 this->EncoderInverted = newEncoderInverted;
457 return *this;
458 }
459
460 /**
461 * \brief Modifies the DriveMotorGearRatio parameter and returns itself.
462 *
463 * Gear ratio between the drive motor and the wheel.
464 *
465 * \param newDriveMotorGearRatio Parameter to modify
466 * \returns this object
467 */
469 {
470 this->DriveMotorGearRatio = newDriveMotorGearRatio;
471 return *this;
472 }
473
474 /**
475 * \brief Modifies the SteerMotorGearRatio parameter and returns itself.
476 *
477 * Gear ratio between the steer motor and the azimuth encoder. For example, the
478 * SDS Mk4 has a steering ratio of 12.8.
479 *
480 * \param newSteerMotorGearRatio Parameter to modify
481 * \returns this object
482 */
484 {
485 this->SteerMotorGearRatio = newSteerMotorGearRatio;
486 return *this;
487 }
488
489 /**
490 * \brief Modifies the CouplingGearRatio parameter and returns itself.
491 *
492 * Coupled gear ratio between the azimuth encoder and the drive motor.
493 *
494 * For a typical swerve module, the azimuth turn motor also drives the wheel a
495 * nontrivial amount, which affects the accuracy of odometry and control. This
496 * ratio represents the number of rotations of the drive motor caused by a
497 * rotation of the azimuth.
498 *
499 * \param newCouplingGearRatio Parameter to modify
500 * \returns this object
501 */
503 {
504 this->CouplingGearRatio = newCouplingGearRatio;
505 return *this;
506 }
507
508 /**
509 * \brief Modifies the WheelRadius parameter and returns itself.
510 *
511 * Radius of the driving wheel in meters.
512 *
513 * \param newWheelRadius Parameter to modify
514 * \returns this object
515 */
517 {
518 this->WheelRadius = newWheelRadius;
519 return *this;
520 }
521
522 /**
523 * \brief Modifies the SteerMotorGains parameter and returns itself.
524 *
525 * The steer motor closed-loop gains.
526 *
527 * The steer motor uses the control ouput type specified by
528 * SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains
529 * operate on azimuth rotations (after the gear ratio).
530 *
531 * \param newSteerMotorGains Parameter to modify
532 * \returns this object
533 */
535 {
536 this->SteerMotorGains = newSteerMotorGains;
537 return *this;
538 }
539
540 /**
541 * \brief Modifies the DriveMotorGains parameter and returns itself.
542 *
543 * The drive motor closed-loop gains.
544 *
545 * When using closed-loop control, the drive motor uses the control output type
546 * specified by DriveMotorClosedLoopOutput and any closed-loop
547 * SwerveModule#DriveRequestType. These gains operate on motor rotor rotations
548 * (before the gear ratio).
549 *
550 * \param newDriveMotorGains Parameter to modify
551 * \returns this object
552 */
554 {
555 this->DriveMotorGains = newDriveMotorGains;
556 return *this;
557 }
558
559 /**
560 * \brief Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
561 *
562 * The closed-loop output type to use for the steer motors.
563 *
564 * \param newSteerMotorClosedLoopOutput Parameter to modify
565 * \returns this object
566 */
568 {
569 this->SteerMotorClosedLoopOutput = newSteerMotorClosedLoopOutput;
570 return *this;
571 }
572
573 /**
574 * \brief Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
575 *
576 * The closed-loop output type to use for the drive motors.
577 *
578 * \param newDriveMotorClosedLoopOutput Parameter to modify
579 * \returns this object
580 */
582 {
583 this->DriveMotorClosedLoopOutput = newDriveMotorClosedLoopOutput;
584 return *this;
585 }
586
587 /**
588 * \brief Modifies the SlipCurrent parameter and returns itself.
589 *
590 * The maximum amount of stator current the drive motors can apply without
591 * slippage.
592 *
593 * \param newSlipCurrent Parameter to modify
594 * \returns this object
595 */
597 {
598 this->SlipCurrent = newSlipCurrent;
599 return *this;
600 }
601
602 /**
603 * \brief Modifies the SpeedAt12Volts parameter and returns itself.
604 *
605 * When using open-loop drive control, this specifies the speed at which the
606 * robot travels when driven with 12 volts. This is used to approximate the
607 * output for a desired velocity. If using closed loop control, this value is
608 * ignored.
609 *
610 * \param newSpeedAt12Volts Parameter to modify
611 * \returns this object
612 */
613 constexpr SwerveModuleConstants<DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT> &WithSpeedAt12Volts(units::velocity::meters_per_second_t newSpeedAt12Volts)
614 {
615 this->SpeedAt12Volts = newSpeedAt12Volts;
616 return *this;
617 }
618
619 /**
620 * \brief Modifies the DriveMotorType parameter and returns itself.
621 *
622 * Choose the motor used for the drive motor.
623 *
624 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
625 * Talon FXS, this should be set to the motor attached to the Talon FXS.
626 *
627 * \param newDriveMotorType Parameter to modify
628 * \returns this object
629 */
631 {
632 this->DriveMotorType = newDriveMotorType;
633 return *this;
634 }
635
636 /**
637 * \brief Modifies the SteerMotorType parameter and returns itself.
638 *
639 * Choose the motor used for the steer motor.
640 *
641 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
642 * Talon FXS, this should be set to the motor attached to the Talon FXS.
643 *
644 * \param newSteerMotorType Parameter to modify
645 * \returns this object
646 */
648 {
649 this->SteerMotorType = newSteerMotorType;
650 return *this;
651 }
652
653 /**
654 * \brief Modifies the FeedbackSource parameter and returns itself.
655 *
656 * Choose how the feedback sensors should be configured.
657 *
658 * If the robot does not support Pro, then this should be set to RemoteCANcoder.
659 * Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder
660 * depending on if there is a risk that the CANcoder can fail in a way to
661 * provide "good" data.
662 *
663 * If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not
664 * Pro-licensed, the device will automatically fall back to RemoteCANcoder and
665 * report a UsingProFeatureOnUnlicensedDevice status code.
666 *
667 * \param newFeedbackSource Parameter to modify
668 * \returns this object
669 */
671 {
672 this->FeedbackSource = newFeedbackSource;
673 return *this;
674 }
675
676 /**
677 * \brief Modifies the DriveMotorInitialConfigs parameter and returns itself.
678 *
679 * The initial configs used to configure the drive motor of the swerve module.
680 * The default value is the factory-default.
681 *
682 * Users may change the initial configuration as they need. Any config that's
683 * not referenced in the SwerveModuleConstants class is available to be changed.
684 *
685 * The list of configs that will be overwritten is as follows:
686 *
687 * - configs#MotorOutputConfigs#NeutralMode (Brake mode, overwritten with
688 * SwerveDrivetrain#ConfigNeutralMode)
689 * - configs#MotorOutputConfigs#Inverted
690 * (SwerveModuleConstants#DriveMotorInverted)
691 * - configs#Slot0Configs (SwerveModuleConstants#DriveMotorGains)
692 * - configs#CurrentLimitsConfigs#StatorCurrentLimit /
693 * configs#TorqueCurrentConfigs#PeakForwardTorqueCurrent /
694 * configs#TorqueCurrentConfigs#PeakReverseTorqueCurrent
695 * (SwerveModuleConstants#SlipCurrent)
696 * - configs#CurrentLimitsConfigs#StatorCurrentLimitEnable (Enabled)
697 *
698 *
699 * \param newDriveMotorInitialConfigs Parameter to modify
700 * \returns this object
701 */
703 {
704 this->DriveMotorInitialConfigs = newDriveMotorInitialConfigs;
705 return *this;
706 }
707
708 /**
709 * \brief Modifies the SteerMotorInitialConfigs parameter and returns itself.
710 *
711 * The initial configs used to configure the steer motor of the swerve module.
712 * The default value is the factory-default.
713 *
714 * Users may change the initial configuration as they need. Any config that's
715 * not referenced in the SwerveModuleConstants class is available to be changed.
716 *
717 * The list of configs that will be overwritten is as follows:
718 *
719 * - configs#MotorOutputConfigs#NeutralMode (Brake mode)
720 * - configs#MotorOutputConfigs#Inverted
721 * (SwerveModuleConstants#SteerMotorInverted)
722 * - configs#Slot0Configs (SwerveModuleConstants#SteerMotorGains)
723 * - configs#FeedbackConfigs#FeedbackRemoteSensorID
724 * (SwerveModuleConstants#EncoderId)
725 * - configs#FeedbackConfigs#FeedbackSensorSource
726 * (SwerveModuleConstants#FeedbackSource)
727 * - configs#FeedbackConfigs#RotorToSensorRatio
728 * (SwerveModuleConstants#SteerMotorGearRatio)
729 * - configs#MotionMagicConfigs#MotionMagicExpo_kV /
730 * configs#MotionMagicConfigs#MotionMagicExpo_kA (Calculated from gear ratios)
731 * - configs#ClosedLoopGeneralConfigs#ContinuousWrap (true)
732 *
733 *
734 * \param newSteerMotorInitialConfigs Parameter to modify
735 * \returns this object
736 */
738 {
739 this->SteerMotorInitialConfigs = newSteerMotorInitialConfigs;
740 return *this;
741 }
742
743 /**
744 * \brief Modifies the EncoderInitialConfigs parameter and returns itself.
745 *
746 * The initial configs used to configure the azimuth encoder of the swerve
747 * module. The default value is the factory-default.
748 *
749 * Users may change the initial configuration as they need. Any config that's
750 * not referenced in the SwerveModuleConstants class is available to be changed.
751 *
752 * For CANcoder, the list of configs that will be overwritten is as follows:
753 *
754 * - configs#MagnetSensorConfigs#MagnetOffset
755 * (SwerveModuleConstants#EncoderOffset)
756 * - configs#MagnetSensorConfigs#SensorDirection
757 * (SwerveModuleConstants#EncoderInverted)
758 *
759 *
760 * \param newEncoderInitialConfigs Parameter to modify
761 * \returns this object
762 */
764 {
765 this->EncoderInitialConfigs = newEncoderInitialConfigs;
766 return *this;
767 }
768
769 /**
770 * \brief Modifies the SteerInertia parameter and returns itself.
771 *
772 * Simulated azimuthal inertia.
773 *
774 * \param newSteerInertia Parameter to modify
775 * \returns this object
776 */
777 constexpr SwerveModuleConstants<DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT> &WithSteerInertia(units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
778 {
779 this->SteerInertia = newSteerInertia;
780 return *this;
781 }
782
783 /**
784 * \brief Modifies the DriveInertia parameter and returns itself.
785 *
786 * Simulated drive inertia.
787 *
788 * \param newDriveInertia Parameter to modify
789 * \returns this object
790 */
791 constexpr SwerveModuleConstants<DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT> &WithDriveInertia(units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
792 {
793 this->DriveInertia = newDriveInertia;
794 return *this;
795 }
796
797 /**
798 * \brief Modifies the SteerFrictionVoltage parameter and returns itself.
799 *
800 * Simulated steer voltage required to overcome friction.
801 *
802 * \param newSteerFrictionVoltage Parameter to modify
803 * \returns this object
804 */
806 {
807 this->SteerFrictionVoltage = newSteerFrictionVoltage;
808 return *this;
809 }
810
811 /**
812 * \brief Modifies the DriveFrictionVoltage parameter and returns itself.
813 *
814 * Simulated drive voltage required to overcome friction.
815 *
816 * \param newDriveFrictionVoltage Parameter to modify
817 * \returns this object
818 */
820 {
821 this->DriveFrictionVoltage = newDriveFrictionVoltage;
822 return *this;
823 }
824
825};
826
827/**
828 * \brief Constants that are common across the swerve modules, used
829 * for creating instances of module-specific SwerveModuleConstants.
830 */
831template <
832 typename DriveMotorConfigsT,
833 typename SteerMotorConfigsT,
834 typename EncoderConfigsT,
835 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, DriveMotorConfigsT>>,
836 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, SteerMotorConfigsT>>,
837 typename = std::enable_if_t<std::is_base_of_v<configs::ParentConfiguration, EncoderConfigsT>>
838>
840 constexpr SwerveModuleConstantsFactory() = default;
841
842 /**
843 * \brief Gear ratio between the drive motor and the wheel.
844 */
845 units::dimensionless::scalar_t DriveMotorGearRatio = 0;
846 /**
847 * \brief Gear ratio between the steer motor and the azimuth encoder. For
848 * example, the SDS Mk4 has a steering ratio of 12.8.
849 */
850 units::dimensionless::scalar_t SteerMotorGearRatio = 0;
851 /**
852 * \brief Coupled gear ratio between the azimuth encoder and the drive motor.
853 *
854 * For a typical swerve module, the azimuth turn motor also drives the wheel a
855 * nontrivial amount, which affects the accuracy of odometry and control. This
856 * ratio represents the number of rotations of the drive motor caused by a
857 * rotation of the azimuth.
858 */
859 units::dimensionless::scalar_t CouplingGearRatio = 0;
860 /**
861 * \brief Radius of the driving wheel in meters.
862 */
863 units::length::meter_t WheelRadius = 0_m;
864 /**
865 * \brief The steer motor closed-loop gains.
866 *
867 * The steer motor uses the control ouput type specified by
868 * SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains
869 * operate on azimuth rotations (after the gear ratio).
870 */
872 /**
873 * \brief The drive motor closed-loop gains.
874 *
875 * When using closed-loop control, the drive motor uses the control output type
876 * specified by DriveMotorClosedLoopOutput and any closed-loop
877 * SwerveModule#DriveRequestType. These gains operate on motor rotor rotations
878 * (before the gear ratio).
879 */
881 /**
882 * \brief The closed-loop output type to use for the steer motors.
883 */
885 /**
886 * \brief The closed-loop output type to use for the drive motors.
887 */
889 /**
890 * \brief The maximum amount of stator current the drive motors can apply
891 * without slippage.
892 */
893 units::current::ampere_t SlipCurrent = 120_A;
894 /**
895 * \brief When using open-loop drive control, this specifies the speed at which
896 * the robot travels when driven with 12 volts. This is used to approximate the
897 * output for a desired velocity. If using closed loop control, this value is
898 * ignored.
899 */
900 units::velocity::meters_per_second_t SpeedAt12Volts = 0_mps;
901 /**
902 * \brief Choose the motor used for the drive motor.
903 *
904 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
905 * Talon FXS, this should be set to the motor attached to the Talon FXS.
906 */
908 /**
909 * \brief Choose the motor used for the steer motor.
910 *
911 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
912 * Talon FXS, this should be set to the motor attached to the Talon FXS.
913 */
915 /**
916 * \brief Choose how the feedback sensors should be configured.
917 *
918 * If the robot does not support Pro, then this should be set to RemoteCANcoder.
919 * Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder
920 * depending on if there is a risk that the CANcoder can fail in a way to
921 * provide "good" data.
922 *
923 * If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not
924 * Pro-licensed, the device will automatically fall back to RemoteCANcoder and
925 * report a UsingProFeatureOnUnlicensedDevice status code.
926 */
928 /**
929 * \brief The initial configs used to configure the drive motor of the swerve
930 * module. The default value is the factory-default.
931 *
932 * Users may change the initial configuration as they need. Any config that's
933 * not referenced in the SwerveModuleConstants class is available to be changed.
934 *
935 * The list of configs that will be overwritten is as follows:
936 *
937 * - configs#MotorOutputConfigs#NeutralMode (Brake mode, overwritten with
938 * SwerveDrivetrain#ConfigNeutralMode)
939 * - configs#MotorOutputConfigs#Inverted
940 * (SwerveModuleConstants#DriveMotorInverted)
941 * - configs#Slot0Configs (SwerveModuleConstants#DriveMotorGains)
942 * - configs#CurrentLimitsConfigs#StatorCurrentLimit /
943 * configs#TorqueCurrentConfigs#PeakForwardTorqueCurrent /
944 * configs#TorqueCurrentConfigs#PeakReverseTorqueCurrent
945 * (SwerveModuleConstants#SlipCurrent)
946 * - configs#CurrentLimitsConfigs#StatorCurrentLimitEnable (Enabled)
947 *
948 */
949 DriveMotorConfigsT DriveMotorInitialConfigs = {};
950 /**
951 * \brief The initial configs used to configure the steer motor of the swerve
952 * module. The default value is the factory-default.
953 *
954 * Users may change the initial configuration as they need. Any config that's
955 * not referenced in the SwerveModuleConstants class is available to be changed.
956 *
957 * The list of configs that will be overwritten is as follows:
958 *
959 * - configs#MotorOutputConfigs#NeutralMode (Brake mode)
960 * - configs#MotorOutputConfigs#Inverted
961 * (SwerveModuleConstants#SteerMotorInverted)
962 * - configs#Slot0Configs (SwerveModuleConstants#SteerMotorGains)
963 * - configs#FeedbackConfigs#FeedbackRemoteSensorID
964 * (SwerveModuleConstants#EncoderId)
965 * - configs#FeedbackConfigs#FeedbackSensorSource
966 * (SwerveModuleConstants#FeedbackSource)
967 * - configs#FeedbackConfigs#RotorToSensorRatio
968 * (SwerveModuleConstants#SteerMotorGearRatio)
969 * - configs#MotionMagicConfigs#MotionMagicExpo_kV /
970 * configs#MotionMagicConfigs#MotionMagicExpo_kA (Calculated from gear ratios)
971 * - configs#ClosedLoopGeneralConfigs#ContinuousWrap (true)
972 *
973 */
974 SteerMotorConfigsT SteerMotorInitialConfigs = {};
975 /**
976 * \brief The initial configs used to configure the azimuth encoder of the
977 * swerve module. The default value is the factory-default.
978 *
979 * Users may change the initial configuration as they need. Any config that's
980 * not referenced in the SwerveModuleConstants class is available to be changed.
981 *
982 * For CANcoder, the list of configs that will be overwritten is as follows:
983 *
984 * - configs#MagnetSensorConfigs#MagnetOffset
985 * (SwerveModuleConstants#EncoderOffset)
986 * - configs#MagnetSensorConfigs#SensorDirection
987 * (SwerveModuleConstants#EncoderInverted)
988 *
989 */
990 EncoderConfigsT EncoderInitialConfigs = {};
991 /**
992 * \brief Simulated azimuthal inertia.
993 */
994 units::moment_of_inertia::kilogram_square_meter_t SteerInertia = 0.00001_kg_sq_m;
995 /**
996 * \brief Simulated drive inertia.
997 */
998 units::moment_of_inertia::kilogram_square_meter_t DriveInertia = 0.001_kg_sq_m;
999 /**
1000 * \brief Simulated steer voltage required to overcome friction.
1001 */
1002 units::voltage::volt_t SteerFrictionVoltage = 0.25_V;
1003 /**
1004 * \brief Simulated drive voltage required to overcome friction.
1005 */
1006 units::voltage::volt_t DriveFrictionVoltage = 0.25_V;
1007
1008 /**
1009 * \brief Modifies the DriveMotorGearRatio parameter and returns itself.
1010 *
1011 * Gear ratio between the drive motor and the wheel.
1012 *
1013 * \param newDriveMotorGearRatio Parameter to modify
1014 * \returns this object
1015 */
1017 {
1018 this->DriveMotorGearRatio = newDriveMotorGearRatio;
1019 return *this;
1020 }
1021
1022 /**
1023 * \brief Modifies the SteerMotorGearRatio parameter and returns itself.
1024 *
1025 * Gear ratio between the steer motor and the azimuth encoder. For example, the
1026 * SDS Mk4 has a steering ratio of 12.8.
1027 *
1028 * \param newSteerMotorGearRatio Parameter to modify
1029 * \returns this object
1030 */
1032 {
1033 this->SteerMotorGearRatio = newSteerMotorGearRatio;
1034 return *this;
1035 }
1036
1037 /**
1038 * \brief Modifies the CouplingGearRatio parameter and returns itself.
1039 *
1040 * Coupled gear ratio between the azimuth encoder and the drive motor.
1041 *
1042 * For a typical swerve module, the azimuth turn motor also drives the wheel a
1043 * nontrivial amount, which affects the accuracy of odometry and control. This
1044 * ratio represents the number of rotations of the drive motor caused by a
1045 * rotation of the azimuth.
1046 *
1047 * \param newCouplingGearRatio Parameter to modify
1048 * \returns this object
1049 */
1051 {
1052 this->CouplingGearRatio = newCouplingGearRatio;
1053 return *this;
1054 }
1055
1056 /**
1057 * \brief Modifies the WheelRadius parameter and returns itself.
1058 *
1059 * Radius of the driving wheel in meters.
1060 *
1061 * \param newWheelRadius Parameter to modify
1062 * \returns this object
1063 */
1065 {
1066 this->WheelRadius = newWheelRadius;
1067 return *this;
1068 }
1069
1070 /**
1071 * \brief Modifies the SteerMotorGains parameter and returns itself.
1072 *
1073 * The steer motor closed-loop gains.
1074 *
1075 * The steer motor uses the control ouput type specified by
1076 * SteerMotorClosedLoopOutput and any SwerveModule#SteerRequestType. These gains
1077 * operate on azimuth rotations (after the gear ratio).
1078 *
1079 * \param newSteerMotorGains Parameter to modify
1080 * \returns this object
1081 */
1083 {
1084 this->SteerMotorGains = newSteerMotorGains;
1085 return *this;
1086 }
1087
1088 /**
1089 * \brief Modifies the DriveMotorGains parameter and returns itself.
1090 *
1091 * The drive motor closed-loop gains.
1092 *
1093 * When using closed-loop control, the drive motor uses the control output type
1094 * specified by DriveMotorClosedLoopOutput and any closed-loop
1095 * SwerveModule#DriveRequestType. These gains operate on motor rotor rotations
1096 * (before the gear ratio).
1097 *
1098 * \param newDriveMotorGains Parameter to modify
1099 * \returns this object
1100 */
1102 {
1103 this->DriveMotorGains = newDriveMotorGains;
1104 return *this;
1105 }
1106
1107 /**
1108 * \brief Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
1109 *
1110 * The closed-loop output type to use for the steer motors.
1111 *
1112 * \param newSteerMotorClosedLoopOutput Parameter to modify
1113 * \returns this object
1114 */
1116 {
1117 this->SteerMotorClosedLoopOutput = newSteerMotorClosedLoopOutput;
1118 return *this;
1119 }
1120
1121 /**
1122 * \brief Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
1123 *
1124 * The closed-loop output type to use for the drive motors.
1125 *
1126 * \param newDriveMotorClosedLoopOutput Parameter to modify
1127 * \returns this object
1128 */
1130 {
1131 this->DriveMotorClosedLoopOutput = newDriveMotorClosedLoopOutput;
1132 return *this;
1133 }
1134
1135 /**
1136 * \brief Modifies the SlipCurrent parameter and returns itself.
1137 *
1138 * The maximum amount of stator current the drive motors can apply without
1139 * slippage.
1140 *
1141 * \param newSlipCurrent Parameter to modify
1142 * \returns this object
1143 */
1145 {
1146 this->SlipCurrent = newSlipCurrent;
1147 return *this;
1148 }
1149
1150 /**
1151 * \brief Modifies the SpeedAt12Volts parameter and returns itself.
1152 *
1153 * When using open-loop drive control, this specifies the speed at which the
1154 * robot travels when driven with 12 volts. This is used to approximate the
1155 * output for a desired velocity. If using closed loop control, this value is
1156 * ignored.
1157 *
1158 * \param newSpeedAt12Volts Parameter to modify
1159 * \returns this object
1160 */
1162 {
1163 this->SpeedAt12Volts = newSpeedAt12Volts;
1164 return *this;
1165 }
1166
1167 /**
1168 * \brief Modifies the DriveMotorType parameter and returns itself.
1169 *
1170 * Choose the motor used for the drive motor.
1171 *
1172 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
1173 * Talon FXS, this should be set to the motor attached to the Talon FXS.
1174 *
1175 * \param newDriveMotorType Parameter to modify
1176 * \returns this object
1177 */
1179 {
1180 this->DriveMotorType = newDriveMotorType;
1181 return *this;
1182 }
1183
1184 /**
1185 * \brief Modifies the SteerMotorType parameter and returns itself.
1186 *
1187 * Choose the motor used for the steer motor.
1188 *
1189 * If using a Talon FX, this should be set to TalonFX_Integrated. If using a
1190 * Talon FXS, this should be set to the motor attached to the Talon FXS.
1191 *
1192 * \param newSteerMotorType Parameter to modify
1193 * \returns this object
1194 */
1196 {
1197 this->SteerMotorType = newSteerMotorType;
1198 return *this;
1199 }
1200
1201 /**
1202 * \brief Modifies the FeedbackSource parameter and returns itself.
1203 *
1204 * Choose how the feedback sensors should be configured.
1205 *
1206 * If the robot does not support Pro, then this should be set to RemoteCANcoder.
1207 * Otherwise, users have the option to use either FusedCANcoder or SyncCANcoder
1208 * depending on if there is a risk that the CANcoder can fail in a way to
1209 * provide "good" data.
1210 *
1211 * If this is set to FusedCANcoder or SyncCANcoder when the steer motor is not
1212 * Pro-licensed, the device will automatically fall back to RemoteCANcoder and
1213 * report a UsingProFeatureOnUnlicensedDevice status code.
1214 *
1215 * \param newFeedbackSource Parameter to modify
1216 * \returns this object
1217 */
1219 {
1220 this->FeedbackSource = newFeedbackSource;
1221 return *this;
1222 }
1223
1224 /**
1225 * \brief Modifies the DriveMotorInitialConfigs parameter and returns itself.
1226 *
1227 * The initial configs used to configure the drive motor of the swerve module.
1228 * The default value is the factory-default.
1229 *
1230 * Users may change the initial configuration as they need. Any config that's
1231 * not referenced in the SwerveModuleConstants class is available to be changed.
1232 *
1233 * The list of configs that will be overwritten is as follows:
1234 *
1235 * - configs#MotorOutputConfigs#NeutralMode (Brake mode, overwritten with
1236 * SwerveDrivetrain#ConfigNeutralMode)
1237 * - configs#MotorOutputConfigs#Inverted
1238 * (SwerveModuleConstants#DriveMotorInverted)
1239 * - configs#Slot0Configs (SwerveModuleConstants#DriveMotorGains)
1240 * - configs#CurrentLimitsConfigs#StatorCurrentLimit /
1241 * configs#TorqueCurrentConfigs#PeakForwardTorqueCurrent /
1242 * configs#TorqueCurrentConfigs#PeakReverseTorqueCurrent
1243 * (SwerveModuleConstants#SlipCurrent)
1244 * - configs#CurrentLimitsConfigs#StatorCurrentLimitEnable (Enabled)
1245 *
1246 *
1247 * \param newDriveMotorInitialConfigs Parameter to modify
1248 * \returns this object
1249 */
1251 {
1252 this->DriveMotorInitialConfigs = newDriveMotorInitialConfigs;
1253 return *this;
1254 }
1255
1256 /**
1257 * \brief Modifies the SteerMotorInitialConfigs parameter and returns itself.
1258 *
1259 * The initial configs used to configure the steer motor of the swerve module.
1260 * The default value is the factory-default.
1261 *
1262 * Users may change the initial configuration as they need. Any config that's
1263 * not referenced in the SwerveModuleConstants class is available to be changed.
1264 *
1265 * The list of configs that will be overwritten is as follows:
1266 *
1267 * - configs#MotorOutputConfigs#NeutralMode (Brake mode)
1268 * - configs#MotorOutputConfigs#Inverted
1269 * (SwerveModuleConstants#SteerMotorInverted)
1270 * - configs#Slot0Configs (SwerveModuleConstants#SteerMotorGains)
1271 * - configs#FeedbackConfigs#FeedbackRemoteSensorID
1272 * (SwerveModuleConstants#EncoderId)
1273 * - configs#FeedbackConfigs#FeedbackSensorSource
1274 * (SwerveModuleConstants#FeedbackSource)
1275 * - configs#FeedbackConfigs#RotorToSensorRatio
1276 * (SwerveModuleConstants#SteerMotorGearRatio)
1277 * - configs#MotionMagicConfigs#MotionMagicExpo_kV /
1278 * configs#MotionMagicConfigs#MotionMagicExpo_kA (Calculated from gear ratios)
1279 * - configs#ClosedLoopGeneralConfigs#ContinuousWrap (true)
1280 *
1281 *
1282 * \param newSteerMotorInitialConfigs Parameter to modify
1283 * \returns this object
1284 */
1286 {
1287 this->SteerMotorInitialConfigs = newSteerMotorInitialConfigs;
1288 return *this;
1289 }
1290
1291 /**
1292 * \brief Modifies the EncoderInitialConfigs parameter and returns itself.
1293 *
1294 * The initial configs used to configure the azimuth encoder of the swerve
1295 * module. The default value is the factory-default.
1296 *
1297 * Users may change the initial configuration as they need. Any config that's
1298 * not referenced in the SwerveModuleConstants class is available to be changed.
1299 *
1300 * For CANcoder, the list of configs that will be overwritten is as follows:
1301 *
1302 * - configs#MagnetSensorConfigs#MagnetOffset
1303 * (SwerveModuleConstants#EncoderOffset)
1304 * - configs#MagnetSensorConfigs#SensorDirection
1305 * (SwerveModuleConstants#EncoderInverted)
1306 *
1307 *
1308 * \param newEncoderInitialConfigs Parameter to modify
1309 * \returns this object
1310 */
1312 {
1313 this->EncoderInitialConfigs = newEncoderInitialConfigs;
1314 return *this;
1315 }
1316
1317 /**
1318 * \brief Modifies the SteerInertia parameter and returns itself.
1319 *
1320 * Simulated azimuthal inertia.
1321 *
1322 * \param newSteerInertia Parameter to modify
1323 * \returns this object
1324 */
1325 constexpr SwerveModuleConstantsFactory<DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT> &WithSteerInertia(units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
1326 {
1327 this->SteerInertia = newSteerInertia;
1328 return *this;
1329 }
1330
1331 /**
1332 * \brief Modifies the DriveInertia parameter and returns itself.
1333 *
1334 * Simulated drive inertia.
1335 *
1336 * \param newDriveInertia Parameter to modify
1337 * \returns this object
1338 */
1339 constexpr SwerveModuleConstantsFactory<DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT> &WithDriveInertia(units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
1340 {
1341 this->DriveInertia = newDriveInertia;
1342 return *this;
1343 }
1344
1345 /**
1346 * \brief Modifies the SteerFrictionVoltage parameter and returns itself.
1347 *
1348 * Simulated steer voltage required to overcome friction.
1349 *
1350 * \param newSteerFrictionVoltage Parameter to modify
1351 * \returns this object
1352 */
1354 {
1355 this->SteerFrictionVoltage = newSteerFrictionVoltage;
1356 return *this;
1357 }
1358
1359 /**
1360 * \brief Modifies the DriveFrictionVoltage parameter and returns itself.
1361 *
1362 * Simulated drive voltage required to overcome friction.
1363 *
1364 * \param newDriveFrictionVoltage Parameter to modify
1365 * \returns this object
1366 */
1368 {
1369 this->DriveFrictionVoltage = newDriveFrictionVoltage;
1370 return *this;
1371 }
1372
1373 /**
1374 * \brief Creates the constants for a swerve module with the given properties.
1375 *
1376 * \param steerMotorId CAN ID of the steer motor.
1377 * \param driveMotorId CAN ID of the drive motor.
1378 * \param encoderId CAN ID of the absolute encoder used for azimuth.
1379 * \param encoderOffset Offset of the azimuth encoder.
1380 * \param locationX The location of this module's wheels relative to the physical center of the robot in meters along the X axis of the robot.
1381 * \param locationY The location of this module's wheels relative to the physical center of the robot in meters along the Y axis of the robot.
1382 * \param driveMotorInverted True if the drive motor is inverted.
1383 * \param steerMotorInverted True if the steer motor is inverted from the azimuth. The azimuth should rotate counter-clockwise (as seen from the top of the robot) for a positive motor output.
1384 * \param encoderInverted True if the azimuth encoder is inverted from the azimuth. The encoder should report a positive velocity when the azimuth rotates counter-clockwise (as seen from the top of the robot).
1385 * \returns Constants for the swerve module
1386 */
1388 int steerMotorId,
1389 int driveMotorId,
1390 int encoderId,
1391 units::angle::turn_t encoderOffset,
1392 units::length::meter_t locationX,
1393 units::length::meter_t locationY,
1394 bool driveMotorInverted,
1395 bool steerMotorInverted,
1396 bool encoderInverted) const
1397 {
1399 .WithSteerMotorId(steerMotorId)
1400 .WithDriveMotorId(driveMotorId)
1401 .WithEncoderId(encoderId)
1402 .WithEncoderOffset(encoderOffset)
1403 .WithLocationX(locationX)
1404 .WithLocationY(locationY)
1405 .WithDriveMotorInverted(driveMotorInverted)
1406 .WithSteerMotorInverted(steerMotorInverted)
1407 .WithEncoderInverted(encoderInverted)
1408 .WithDriveMotorGearRatio(DriveMotorGearRatio)
1409 .WithSteerMotorGearRatio(SteerMotorGearRatio)
1410 .WithCouplingGearRatio(CouplingGearRatio)
1411 .WithWheelRadius(WheelRadius)
1412 .WithSteerMotorGains(SteerMotorGains)
1413 .WithDriveMotorGains(DriveMotorGains)
1414 .WithSteerMotorClosedLoopOutput(SteerMotorClosedLoopOutput)
1415 .WithDriveMotorClosedLoopOutput(DriveMotorClosedLoopOutput)
1416 .WithSlipCurrent(SlipCurrent)
1417 .WithSpeedAt12Volts(SpeedAt12Volts)
1418 .WithDriveMotorType(DriveMotorType)
1419 .WithSteerMotorType(SteerMotorType)
1420 .WithFeedbackSource(FeedbackSource)
1421 .WithDriveMotorInitialConfigs(DriveMotorInitialConfigs)
1422 .WithSteerMotorInitialConfigs(SteerMotorInitialConfigs)
1423 .WithEncoderInitialConfigs(EncoderInitialConfigs)
1424 .WithSteerInertia(SteerInertia)
1425 .WithDriveInertia(DriveInertia)
1426 .WithSteerFrictionVoltage(SteerFrictionVoltage)
1427 .WithDriveFrictionVoltage(DriveFrictionVoltage);
1428 }
1429};
1430
1431}
1432}
1433}
Gains for the specified slot.
Definition Configs.hpp:4279
ClosedLoopOutputType
Supported closed-loop output types.
Definition SwerveModuleConstants.hpp:23
SteerMotorArrangement
Supported motor arrangements for the steer motors.
Definition SwerveModuleConstants.hpp:50
@ TalonFXS_Brushed_AC
Brushed motor connected to a Talon FXS on terminals A and C.
@ TalonFXS_Brushed_AB
Brushed motor connected to a Talon FXS on terminals A and B.
@ TalonFX_Integrated
Talon FX integrated brushless motor.
@ TalonFXS_Brushed_BC
Brushed motor connected to a Talon FXS on terminals B and C.
@ TalonFXS_NEO550_JST
Third party NEO550 brushless motor connected to a Talon FXS over JST.
@ TalonFXS_Minion_JST
CTR Electronics MinionĀ® brushless motor connected to a Talon FXS over JST.
SteerFeedbackType
Supported feedback sensors for the steer motors.
Definition SwerveModuleConstants.hpp:88
@ FusedCANcoder
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANcoder for the steer motor.
@ SyncCANcoder
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANcoder for the steer motor.
@ RemoteCANcoder
Use signals::FeedbackSensorSourceValue::RemoteCANcoder for the steer motor.
DriveMotorArrangement
Supported motor arrangements for the drive motors.
Definition SwerveModuleConstants.hpp:32
@ TalonFX_Integrated
Talon FX integrated brushless motor.
@ TalonFXS_NEO_JST
Third party NEO brushless motor connected to a Talon FXS over JST.
@ TalonFXS_VORTEX_JST
Third party VORTEX brushless motor connected to a Talon FXS over JST.
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18
Constants that are common across the swerve modules, used for creating instances of module-specific S...
Definition SwerveModuleConstants.hpp:839
SteerMotorArrangement SteerMotorType
Choose the motor used for the steer motor.
Definition SwerveModuleConstants.hpp:914
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerFrictionVoltage(units::voltage::volt_t newSteerFrictionVoltage)
Modifies the SteerFrictionVoltage parameter and returns itself.
Definition SwerveModuleConstants.hpp:1353
units::current::ampere_t SlipCurrent
The maximum amount of stator current the drive motors can apply without slippage.
Definition SwerveModuleConstants.hpp:893
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSpeedAt12Volts(units::velocity::meters_per_second_t newSpeedAt12Volts)
Modifies the SpeedAt12Volts parameter and returns itself.
Definition SwerveModuleConstants.hpp:1161
units::moment_of_inertia::kilogram_square_meter_t DriveInertia
Simulated drive inertia.
Definition SwerveModuleConstants.hpp:998
EncoderConfigsT EncoderInitialConfigs
The initial configs used to configure the azimuth encoder of the swerve module.
Definition SwerveModuleConstants.hpp:990
configs::Slot0Configs DriveMotorGains
The drive motor closed-loop gains.
Definition SwerveModuleConstants.hpp:880
units::velocity::meters_per_second_t SpeedAt12Volts
When using open-loop drive control, this specifies the speed at which the robot travels when driven w...
Definition SwerveModuleConstants.hpp:900
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveFrictionVoltage(units::voltage::volt_t newDriveFrictionVoltage)
Modifies the DriveFrictionVoltage parameter and returns itself.
Definition SwerveModuleConstants.hpp:1367
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithFeedbackSource(SteerFeedbackType newFeedbackSource)
Modifies the FeedbackSource parameter and returns itself.
Definition SwerveModuleConstants.hpp:1218
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorGearRatio(units::dimensionless::scalar_t newSteerMotorGearRatio)
Modifies the SteerMotorGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:1031
units::voltage::volt_t SteerFrictionVoltage
Simulated steer voltage required to overcome friction.
Definition SwerveModuleConstants.hpp:1002
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorInitialConfigs(DriveMotorConfigsT newDriveMotorInitialConfigs)
Modifies the DriveMotorInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:1250
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > CreateModuleConstants(int steerMotorId, int driveMotorId, int encoderId, units::angle::turn_t encoderOffset, units::length::meter_t locationX, units::length::meter_t locationY, bool driveMotorInverted, bool steerMotorInverted, bool encoderInverted) const
Creates the constants for a swerve module with the given properties.
Definition SwerveModuleConstants.hpp:1387
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorType(DriveMotorArrangement newDriveMotorType)
Modifies the DriveMotorType parameter and returns itself.
Definition SwerveModuleConstants.hpp:1178
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithCouplingGearRatio(units::dimensionless::scalar_t newCouplingGearRatio)
Modifies the CouplingGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:1050
units::dimensionless::scalar_t DriveMotorGearRatio
Gear ratio between the drive motor and the wheel.
Definition SwerveModuleConstants.hpp:845
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorClosedLoopOutput(ClosedLoopOutputType newSteerMotorClosedLoopOutput)
Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
Definition SwerveModuleConstants.hpp:1115
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerInertia(units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
Modifies the SteerInertia parameter and returns itself.
Definition SwerveModuleConstants.hpp:1325
units::length::meter_t WheelRadius
Radius of the driving wheel in meters.
Definition SwerveModuleConstants.hpp:863
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorClosedLoopOutput(ClosedLoopOutputType newDriveMotorClosedLoopOutput)
Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
Definition SwerveModuleConstants.hpp:1129
units::voltage::volt_t DriveFrictionVoltage
Simulated drive voltage required to overcome friction.
Definition SwerveModuleConstants.hpp:1006
DriveMotorArrangement DriveMotorType
Choose the motor used for the drive motor.
Definition SwerveModuleConstants.hpp:907
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveInertia(units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
Modifies the DriveInertia parameter and returns itself.
Definition SwerveModuleConstants.hpp:1339
units::dimensionless::scalar_t CouplingGearRatio
Coupled gear ratio between the azimuth encoder and the drive motor.
Definition SwerveModuleConstants.hpp:859
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorInitialConfigs(SteerMotorConfigsT newSteerMotorInitialConfigs)
Modifies the SteerMotorInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:1285
SteerMotorConfigsT SteerMotorInitialConfigs
The initial configs used to configure the steer motor of the swerve module.
Definition SwerveModuleConstants.hpp:974
ClosedLoopOutputType DriveMotorClosedLoopOutput
The closed-loop output type to use for the drive motors.
Definition SwerveModuleConstants.hpp:888
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithWheelRadius(units::length::meter_t newWheelRadius)
Modifies the WheelRadius parameter and returns itself.
Definition SwerveModuleConstants.hpp:1064
units::dimensionless::scalar_t SteerMotorGearRatio
Gear ratio between the steer motor and the azimuth encoder.
Definition SwerveModuleConstants.hpp:850
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorGains(configs::Slot0Configs newSteerMotorGains)
Modifies the SteerMotorGains parameter and returns itself.
Definition SwerveModuleConstants.hpp:1082
SteerFeedbackType FeedbackSource
Choose how the feedback sensors should be configured.
Definition SwerveModuleConstants.hpp:927
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorGearRatio(units::dimensionless::scalar_t newDriveMotorGearRatio)
Modifies the DriveMotorGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:1016
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSlipCurrent(units::current::ampere_t newSlipCurrent)
Modifies the SlipCurrent parameter and returns itself.
Definition SwerveModuleConstants.hpp:1144
units::moment_of_inertia::kilogram_square_meter_t SteerInertia
Simulated azimuthal inertia.
Definition SwerveModuleConstants.hpp:994
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorType(SteerMotorArrangement newSteerMotorType)
Modifies the SteerMotorType parameter and returns itself.
Definition SwerveModuleConstants.hpp:1195
configs::Slot0Configs SteerMotorGains
The steer motor closed-loop gains.
Definition SwerveModuleConstants.hpp:871
DriveMotorConfigsT DriveMotorInitialConfigs
The initial configs used to configure the drive motor of the swerve module.
Definition SwerveModuleConstants.hpp:949
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorGains(configs::Slot0Configs newDriveMotorGains)
Modifies the DriveMotorGains parameter and returns itself.
Definition SwerveModuleConstants.hpp:1101
ClosedLoopOutputType SteerMotorClosedLoopOutput
The closed-loop output type to use for the steer motors.
Definition SwerveModuleConstants.hpp:884
constexpr SwerveModuleConstantsFactory< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithEncoderInitialConfigs(EncoderConfigsT newEncoderInitialConfigs)
Modifies the EncoderInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:1311
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:117
DriveMotorArrangement DriveMotorType
Choose the motor used for the drive motor.
Definition SwerveModuleConstants.hpp:227
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithEncoderInitialConfigs(const EncoderConfigsT &newEncoderInitialConfigs)
Modifies the EncoderInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:763
bool DriveMotorInverted
True if the drive motor is inverted.
Definition SwerveModuleConstants.hpp:149
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorGearRatio(units::dimensionless::scalar_t newSteerMotorGearRatio)
Modifies the SteerMotorGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:483
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithLocationX(units::length::meter_t newLocationX)
Modifies the LocationX parameter and returns itself.
Definition SwerveModuleConstants.hpp:393
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithEncoderOffset(units::angle::turn_t newEncoderOffset)
Modifies the EncoderOffset parameter and returns itself.
Definition SwerveModuleConstants.hpp:378
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithEncoderInverted(bool newEncoderInverted)
Modifies the EncoderInverted parameter and returns itself.
Definition SwerveModuleConstants.hpp:454
units::length::meter_t LocationY
The location of this module's wheels relative to the physical center of the robot in meters along the...
Definition SwerveModuleConstants.hpp:145
configs::Slot0Configs SteerMotorGains
The steer motor closed-loop gains.
Definition SwerveModuleConstants.hpp:191
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerFrictionVoltage(units::voltage::volt_t newSteerFrictionVoltage)
Modifies the SteerFrictionVoltage parameter and returns itself.
Definition SwerveModuleConstants.hpp:805
SteerFeedbackType FeedbackSource
Choose how the feedback sensors should be configured.
Definition SwerveModuleConstants.hpp:247
EncoderConfigsT EncoderInitialConfigs
The initial configs used to configure the azimuth encoder of the swerve module.
Definition SwerveModuleConstants.hpp:310
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorInitialConfigs(const DriveMotorConfigsT &newDriveMotorInitialConfigs)
Modifies the DriveMotorInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:702
units::angle::turn_t EncoderOffset
Offset of the azimuth encoder.
Definition SwerveModuleConstants.hpp:135
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithEncoderId(int newEncoderId)
Modifies the EncoderId parameter and returns itself.
Definition SwerveModuleConstants.hpp:364
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithFeedbackSource(SteerFeedbackType newFeedbackSource)
Modifies the FeedbackSource parameter and returns itself.
Definition SwerveModuleConstants.hpp:670
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorInverted(bool newSteerMotorInverted)
Modifies the SteerMotorInverted parameter and returns itself.
Definition SwerveModuleConstants.hpp:438
SteerMotorConfigsT SteerMotorInitialConfigs
The initial configs used to configure the steer motor of the swerve module.
Definition SwerveModuleConstants.hpp:294
units::moment_of_inertia::kilogram_square_meter_t SteerInertia
Simulated azimuthal inertia.
Definition SwerveModuleConstants.hpp:314
units::current::ampere_t SlipCurrent
The maximum amount of stator current the drive motors can apply without slippage.
Definition SwerveModuleConstants.hpp:213
int SteerMotorId
CAN ID of the steer motor.
Definition SwerveModuleConstants.hpp:123
units::length::meter_t LocationX
The location of this module's wheels relative to the physical center of the robot in meters along the...
Definition SwerveModuleConstants.hpp:140
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorType(DriveMotorArrangement newDriveMotorType)
Modifies the DriveMotorType parameter and returns itself.
Definition SwerveModuleConstants.hpp:630
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithCouplingGearRatio(units::dimensionless::scalar_t newCouplingGearRatio)
Modifies the CouplingGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:502
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorId(int newSteerMotorId)
Modifies the SteerMotorId parameter and returns itself.
Definition SwerveModuleConstants.hpp:336
units::velocity::meters_per_second_t SpeedAt12Volts
When using open-loop drive control, this specifies the speed at which the robot travels when driven w...
Definition SwerveModuleConstants.hpp:220
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorGains(const configs::Slot0Configs &newDriveMotorGains)
Modifies the DriveMotorGains parameter and returns itself.
Definition SwerveModuleConstants.hpp:553
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorGearRatio(units::dimensionless::scalar_t newDriveMotorGearRatio)
Modifies the DriveMotorGearRatio parameter and returns itself.
Definition SwerveModuleConstants.hpp:468
units::moment_of_inertia::kilogram_square_meter_t DriveInertia
Simulated drive inertia.
Definition SwerveModuleConstants.hpp:318
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorClosedLoopOutput(ClosedLoopOutputType newSteerMotorClosedLoopOutput)
Modifies the SteerMotorClosedLoopOutput parameter and returns itself.
Definition SwerveModuleConstants.hpp:567
units::voltage::volt_t SteerFrictionVoltage
Simulated steer voltage required to overcome friction.
Definition SwerveModuleConstants.hpp:322
ClosedLoopOutputType SteerMotorClosedLoopOutput
The closed-loop output type to use for the steer motors.
Definition SwerveModuleConstants.hpp:204
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerInertia(units::moment_of_inertia::kilogram_square_meter_t newSteerInertia)
Modifies the SteerInertia parameter and returns itself.
Definition SwerveModuleConstants.hpp:777
DriveMotorConfigsT DriveMotorInitialConfigs
The initial configs used to configure the drive motor of the swerve module.
Definition SwerveModuleConstants.hpp:269
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorId(int newDriveMotorId)
Modifies the DriveMotorId parameter and returns itself.
Definition SwerveModuleConstants.hpp:350
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorInverted(bool newDriveMotorInverted)
Modifies the DriveMotorInverted parameter and returns itself.
Definition SwerveModuleConstants.hpp:422
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithLocationY(units::length::meter_t newLocationY)
Modifies the LocationY parameter and returns itself.
Definition SwerveModuleConstants.hpp:408
units::voltage::volt_t DriveFrictionVoltage
Simulated drive voltage required to overcome friction.
Definition SwerveModuleConstants.hpp:326
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorGains(const configs::Slot0Configs &newSteerMotorGains)
Modifies the SteerMotorGains parameter and returns itself.
Definition SwerveModuleConstants.hpp:534
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorInitialConfigs(const SteerMotorConfigsT &newSteerMotorInitialConfigs)
Modifies the SteerMotorInitialConfigs parameter and returns itself.
Definition SwerveModuleConstants.hpp:737
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveInertia(units::moment_of_inertia::kilogram_square_meter_t newDriveInertia)
Modifies the DriveInertia parameter and returns itself.
Definition SwerveModuleConstants.hpp:791
bool EncoderInverted
True if the azimuth encoder is inverted from the azimuth.
Definition SwerveModuleConstants.hpp:161
int DriveMotorId
CAN ID of the drive motor.
Definition SwerveModuleConstants.hpp:127
units::dimensionless::scalar_t CouplingGearRatio
Coupled gear ratio between the azimuth encoder and the drive motor.
Definition SwerveModuleConstants.hpp:179
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveMotorClosedLoopOutput(ClosedLoopOutputType newDriveMotorClosedLoopOutput)
Modifies the DriveMotorClosedLoopOutput parameter and returns itself.
Definition SwerveModuleConstants.hpp:581
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSpeedAt12Volts(units::velocity::meters_per_second_t newSpeedAt12Volts)
Modifies the SpeedAt12Volts parameter and returns itself.
Definition SwerveModuleConstants.hpp:613
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithDriveFrictionVoltage(units::voltage::volt_t newDriveFrictionVoltage)
Modifies the DriveFrictionVoltage parameter and returns itself.
Definition SwerveModuleConstants.hpp:819
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSlipCurrent(units::current::ampere_t newSlipCurrent)
Modifies the SlipCurrent parameter and returns itself.
Definition SwerveModuleConstants.hpp:596
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithWheelRadius(units::length::meter_t newWheelRadius)
Modifies the WheelRadius parameter and returns itself.
Definition SwerveModuleConstants.hpp:516
bool SteerMotorInverted
True if the steer motor is inverted from the azimuth.
Definition SwerveModuleConstants.hpp:155
units::length::meter_t WheelRadius
Radius of the driving wheel in meters.
Definition SwerveModuleConstants.hpp:183
ClosedLoopOutputType DriveMotorClosedLoopOutput
The closed-loop output type to use for the drive motors.
Definition SwerveModuleConstants.hpp:208
units::dimensionless::scalar_t DriveMotorGearRatio
Gear ratio between the drive motor and the wheel.
Definition SwerveModuleConstants.hpp:165
int EncoderId
CAN ID of the absolute encoder used for azimuth.
Definition SwerveModuleConstants.hpp:131
constexpr SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > & WithSteerMotorType(SteerMotorArrangement newSteerMotorType)
Modifies the SteerMotorType parameter and returns itself.
Definition SwerveModuleConstants.hpp:647
units::dimensionless::scalar_t SteerMotorGearRatio
Gear ratio between the steer motor and the azimuth encoder.
Definition SwerveModuleConstants.hpp:170
SteerMotorArrangement SteerMotorType
Choose the motor used for the steer motor.
Definition SwerveModuleConstants.hpp:234
configs::Slot0Configs DriveMotorGains
The drive motor closed-loop gains.
Definition SwerveModuleConstants.hpp:200