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