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