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