CTRE Phoenix 6 C++ 26.50.0-alpha-1
Loading...
Searching...
No Matches
SwerveModule.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
11namespace ctre {
12namespace phoenix6 {
13
14/* forward decls */
15namespace hardware {
16 class CANcoder;
17 class CANdi;
18 class TalonFX;
19 class TalonFXS;
20}
21namespace configs {
26}
27
28namespace swerve {
29
32
33/**
34 * \brief Swerve Module class that encapsulates a swerve module powered by
35 * CTR Electronics devices.
36 *
37 * This class handles the hardware devices and configures them for
38 * swerve module operation using the Phoenix 6 API.
39 *
40 * This class constructs hardware devices internally, so the user
41 * only specifies the constants (IDs, PID gains, gear ratios, etc).
42 * Getters for these hardware devices are available.
43 */
44template <
45 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
46 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
47 typename EncoderT
48>
49 requires std::same_as<EncoderT, hardware::CANcoder> ||
50 std::same_as<EncoderT, hardware::CANdi> ||
51 std::same_as<EncoderT, hardware::TalonFXS>
53public:
54 /**
55 * \brief Contains everything the swerve module needs to apply a request.
56 */
58
59 /**
60 * \brief All constants for a swerve module.
61 */
63
64protected:
65 /** \brief Number of times to attempt config applies. */
66 static constexpr int kNumConfigAttempts = 2;
67
68 /** \brief The underlying swerve module instance. */
70
71private:
72 DriveMotorT _driveMotor;
73 SteerMotorT _steerMotor;
74 EncoderT _encoder;
75
76public:
77 /**
78 * \brief Construct a SwerveModule with the specified constants.
79 *
80 * \param constants Constants used to construct the module
81 * \param canbus The CAN bus this module is on
82 * \param module The impl#SwerveModuleImpl to use
83 */
84 SwerveModule(Constants const &constants, CANBus canbus, impl::SwerveModuleImpl &module) :
85 _module{&module},
86 _driveMotor{constants.DriveMotorId, canbus},
87 _steerMotor{constants.SteerMotorId, canbus},
88 _encoder{constants.EncoderId, canbus}
89 {
91
92 typename DriveMotorT::Configuration driveConfigs = constants.DriveMotorInitialConfigs;
93 driveConfigs.MotorOutput.NeutralMode = signals::NeutralModeValue::Brake;
94
95 driveConfigs.Slot0 = constants.DriveMotorGains;
96 if constexpr (!std::same_as<configs::TalonFXSConfiguration, decltype(driveConfigs)>) {
97 driveConfigs.TorqueCurrent.PeakForwardTorqueCurrent = constants.SlipCurrent;
98 driveConfigs.TorqueCurrent.PeakReverseTorqueCurrent = -constants.SlipCurrent;
99 }
100 driveConfigs.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent;
101 driveConfigs.CurrentLimits.StatorCurrentLimitEnable = true;
102
103 if constexpr (std::same_as<configs::TalonFXSConfiguration, decltype(driveConfigs)>) {
104 driveConfigs.ExternalFeedback.RotorToSensorRatio = 1.0;
105 driveConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
106
107 switch (constants.DriveMotorType) {
109 printf(
110 "Cannot use TalonFX_Integrated drive motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
111 GetDriveMotor().GetDeviceID()
112 );
113 break;
114
116 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
117 break;
119 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
120 break;
121 }
122 } else {
123 driveConfigs.Feedback.RotorToSensorRatio = 1.0;
124 driveConfigs.Feedback.SensorToMechanismRatio = 1.0;
125
127 printf("Drive motor Talon FX ID %d only supports TalonFX_Integrated.", GetDriveMotor().GetDeviceID());
128 }
129 }
130
131 driveConfigs.MotorOutput.Inverted = constants.DriveMotorInverted
134 for (int i = 0; i < kNumConfigAttempts; ++i) {
135 response = GetDriveMotor().GetConfigurator().Apply(driveConfigs);
136 if (response.IsOK()) break;
137 }
138 if (!response.IsOK()) {
139 printf("Talon ID %d failed config with error %s\n", GetDriveMotor().GetDeviceID(), response.GetName());
140 }
141
142 typename SteerMotorT::Configuration steerConfigs = constants.SteerMotorInitialConfigs;
143 steerConfigs.MotorOutput.NeutralMode = signals::NeutralModeValue::Brake;
144
145 steerConfigs.Slot0 = constants.SteerMotorGains;
146
147 if constexpr (std::same_as<configs::TalonFXSConfiguration, decltype(steerConfigs)>) {
148 switch (constants.SteerMotorType) {
150 printf(
151 "Cannot use TalonFX_Integrated steer motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
152 GetSteerMotor().GetDeviceID()
153 );
154 break;
155
157 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Minion_JST;
158 break;
160 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
161 break;
163 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
164 break;
166 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO550_JST;
167 break;
169 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
170 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_B;
171 break;
173 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
174 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_C;
175 break;
177 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
178 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_B_and_C;
179 break;
180 }
181
182 /* Modify configuration to use remote encoder setting */
183 steerConfigs.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId;
184 switch (constants.FeedbackSource) {
186 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANcoder;
187 break;
189 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANcoder;
190 break;
192 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANcoder;
193 break;
194
196 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM1;
197 break;
199 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM2;
200 break;
202 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM1;
203 break;
205 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM2;
206 break;
208 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM1;
209 break;
211 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM2;
212 break;
213
215 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::PulseWidth;
216 steerConfigs.ExternalFeedback.AbsoluteSensorOffset = constants.EncoderOffset;
217 steerConfigs.ExternalFeedback.SensorPhase = constants.EncoderInverted
220 break;
221 }
222 steerConfigs.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
223 steerConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
224 } else {
226 printf("Steer motor Talon FX ID %d only supports TalonFX_Integrated.", GetSteerMotor().GetDeviceID());
227 }
228
229 /* Modify configuration to use remote encoder setting */
230 steerConfigs.Feedback.FeedbackRemoteSensorID = constants.EncoderId;
231 switch (constants.FeedbackSource) {
233 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANcoder;
234 break;
236 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANcoder;
237 break;
239 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANcoder;
240 break;
241
243 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM1;
244 break;
246 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM2;
247 break;
249 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM1;
250 break;
252 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM2;
253 break;
255 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM1;
256 break;
258 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM2;
259 break;
260
262 printf(
263 "Cannot use Pulse Width steer feedback type on Talon FX ID %d. Pulse Width is only supported on Talon FXS.\n",
264 GetSteerMotor().GetDeviceID()
265 );
266 break;
267 }
268 steerConfigs.Feedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
269 steerConfigs.Feedback.SensorToMechanismRatio = 1.0;
270 }
271
272 steerConfigs.MotionMagic.MotionMagicExpo_kV = 0.12_V / 1_tps * constants.SteerMotorGearRatio;
273 steerConfigs.MotionMagic.MotionMagicExpo_kA = 1.2_V / 1_tr_per_s_sq / constants.SteerMotorGearRatio;
274
275 steerConfigs.ClosedLoopGeneral.ContinuousWrap = true; // Enable continuous wrap for swerve modules
276
277 steerConfigs.MotorOutput.Inverted = constants.SteerMotorInverted
280 for (int i = 0; i < kNumConfigAttempts; ++i) {
281 response = GetSteerMotor().GetConfigurator().Apply(steerConfigs);
282 if (response.IsOK()) break;
283 }
284 if (!response.IsOK()) {
285 printf("Talon ID %d failed config with error %s\n", GetSteerMotor().GetDeviceID(), response.GetName());
286 }
287
288 typename EncoderT::Configuration encoderConfigs = constants.EncoderInitialConfigs;
289 if constexpr (std::same_as<configs::CANcoderConfiguration, decltype(encoderConfigs)>) {
290 encoderConfigs.MagnetSensor.MagnetOffset = constants.EncoderOffset;
291 encoderConfigs.MagnetSensor.SensorDirection = constants.EncoderInverted
294
295 for (int i = 0; i < kNumConfigAttempts; ++i) {
296 response = GetEncoder().GetConfigurator().Apply(encoderConfigs);
297 if (response.IsOK()) break;
298 }
299 if (!response.IsOK()) {
300 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
301 }
302 } else if constexpr (std::same_as<configs::CANdiConfiguration, decltype(encoderConfigs)>) {
303 for (int i = 0; i < kNumConfigAttempts; ++i) {
304 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.DigitalInputs);
305 if (response.IsOK()) break;
306 }
307 if (!response.IsOK()) {
308 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
309 }
310
311 for (int i = 0; i < kNumConfigAttempts; ++i) {
312 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.CustomParams);
313 if (response.IsOK()) break;
314 }
315 if (!response.IsOK()) {
316 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
317 }
318
319 switch (constants.FeedbackSource) {
323 encoderConfigs.PWM1.AbsoluteSensorOffset = constants.EncoderOffset;
324 encoderConfigs.PWM1.SensorDirection = constants.EncoderInverted;
325
326 for (int i = 0; i < kNumConfigAttempts; ++i) {
327 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM1);
328 if (response.IsOK()) break;
329 }
330 if (!response.IsOK()) {
331 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
332 }
333 break;
334
338 encoderConfigs.PWM2.AbsoluteSensorOffset = constants.EncoderOffset;
339 encoderConfigs.PWM2.SensorDirection = constants.EncoderInverted;
340
341 for (int i = 0; i < kNumConfigAttempts; ++i) {
342 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM2);
343 if (response.IsOK()) break;
344 }
345 if (!response.IsOK()) {
346 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
347 }
348 break;
349
350 default:
351 break;
352 }
353 }
354 }
355
356 virtual ~SwerveModule() = default;
357
358 /**
359 * \brief Applies the desired ModuleRequest to this module.
360 *
361 * \param moduleRequest The request to apply to this module
362 */
363 virtual void Apply(ModuleRequest const &moduleRequest)
364 {
365 return _module->Apply(moduleRequest);
366 }
367
368 /**
369 * \brief Controls this module using the specified drive and steer control requests.
370 *
371 * This is intended only to be used for characterization of the robot; do not use this for normal use.
372 *
373 * \param driveRequest The control request to apply to the drive motor
374 * \param steerRequest The control request to apply to the steer motor
375 */
376 template <
377 std::derived_from<controls::ControlRequest> DriveReq,
378 std::derived_from<controls::ControlRequest> SteerReq
379 >
380 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
381 {
382 return _module->Apply(std::forward<DriveReq>(driveRequest), std::forward<SteerReq>(steerRequest));
383 }
384
385 /**
386 * \brief Gets the state of this module and passes it back as a
387 * SwerveModulePosition object with latency compensated values.
388 *
389 * This function is blocking when it performs a refresh.
390 *
391 * \param refresh True if the signals should be refreshed
392 * \returns SwerveModulePosition containing this module's state.
393 */
394 SwerveModulePosition GetPosition(bool refresh)
395 {
396 return _module->GetPosition(refresh);
397 }
398
399 /**
400 * \brief Gets the last cached swerve module position.
401 * This differs from #GetPosition in that it will not
402 * perform any latency compensation or refresh the signals.
403 *
404 * \returns Last cached SwerveModulePosition
405 */
406 SwerveModulePosition GetCachedPosition() const
407 {
408 return _module->GetCachedPosition();
409 }
410
411 /**
412 * \brief Get the current velocity of the module.
413 *
414 * This is typically used for telemetry, as the SwerveModulePosition
415 * is used for odometry.
416 *
417 * \returns Current velocity of the module
418 */
419 SwerveModuleVelocity GetCurrentVelocity() const
420 {
421 return _module->GetCurrentVelocity();
422 }
423
424 /**
425 * \brief Get the target velocity of the module.
426 *
427 * This is typically used for telemetry.
428 *
429 * \returns Target velocity of the module
430 */
431 SwerveModuleVelocity GetTargetVelocity() const
432 {
433 return _module->GetTargetVelocity();
434 }
435
436 /**
437 * \brief Resets this module's drive motor position to 0 rotations.
438 */
439 virtual void ResetPosition()
440 {
441 return _module->ResetPosition();
442 }
443
444 /**
445 * \brief Gets the closed-loop output type to use for the drive motor.
446 *
447 * \returns Drive motor closed-loop output type
448 */
450 {
451 return _module->GetDriveClosedLoopOutputType();
452 }
453
454 /**
455 * \brief Gets the closed-loop output type to use for the steer motor.
456 *
457 * \returns Steer motor closed-loop output type
458 */
460 {
461 return _module->GetSteerClosedLoopOutputType();
462 }
463
464 /**
465 * \brief Gets this module's Drive Motor reference.
466 *
467 * This should be used only to access signals and change configurations that the
468 * swerve drivetrain does not configure itself.
469 *
470 * \returns This module's Drive Motor reference
471 */
472 DriveMotorT &GetDriveMotor()
473 {
474 return _driveMotor;
475 }
476 /**
477 * \brief Gets this module's Drive Motor reference.
478 *
479 * This should be used only to access signals and change configurations that the
480 * swerve drivetrain does not configure itself.
481 *
482 * \returns This module's Drive Motor reference
483 */
484 DriveMotorT const &GetDriveMotor() const
485 {
486 return _driveMotor;
487 }
488
489 /**
490 * \brief Gets this module's Steer Motor reference.
491 *
492 * This should be used only to access signals and change configurations that the
493 * swerve drivetrain does not configure itself.
494 *
495 * \returns This module's Steer Motor reference
496 */
497 SteerMotorT &GetSteerMotor()
498 {
499 return _steerMotor;
500 }
501 /**
502 * \brief Gets this module's Steer Motor reference.
503 *
504 * This should be used only to access signals and change configurations that the
505 * swerve drivetrain does not configure itself.
506 *
507 * \returns This module's Steer Motor reference
508 */
509 SteerMotorT const &GetSteerMotor() const
510 {
511 return _steerMotor;
512 }
513
514 /**
515 * \brief Gets this module's azimuth encoder reference.
516 *
517 * This should be used only to access signals and change configurations that the
518 * swerve drivetrain does not configure itself.
519 *
520 * \returns This module's azimuth encoder reference
521 */
522 EncoderT &GetEncoder()
523 {
524 return _encoder;
525 }
526 /**
527 * \brief Gets this module's azimuth encoder reference.
528 *
529 * This should be used only to access signals and change configurations that the
530 * swerve drivetrain does not configure itself.
531 *
532 * \returns This module's azimuth encoder reference
533 */
534 EncoderT const &GetEncoder() const
535 {
536 return _encoder;
537 }
538};
539
540}
541}
542}
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Class for CANcoder, a CAN based magnetic encoder that provides absolute and relative position along w...
Definition CoreCANcoder.hpp:40
Class for CTR Electronics' CANdi™ branded device, a device that integrates digital signals into the e...
Definition CoreCANdi.hpp:45
Class description for the Talon FX integrated motor controller.
Definition CoreTalonFX.hpp:158
Class description for the Talon FXS motor controller.
Definition CoreTalonFXS.hpp:133
Class for CANcoder, a CAN based magnetic encoder that provides absolute and relative position along w...
Definition CANcoder.hpp:26
Class for CTR Electronics' CANdi™ branded device, a device that integrates digital signals into the e...
Definition CANdi.hpp:26
Class description for the Talon FX integrated motor controller.
Definition TalonFX.hpp:26
Class description for the Talon FXS motor controller.
Definition TalonFXS.hpp:26
impl::SwerveModuleImpl::ModuleRequest ModuleRequest
Contains everything the swerve module needs to apply a request.
Definition SwerveModule.hpp:57
virtual void Apply(ModuleRequest const &moduleRequest)
Applies the desired ModuleRequest to this module.
Definition SwerveModule.hpp:363
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModule.hpp:406
SteerMotorT & GetSteerMotor()
Gets this module's Steer Motor reference.
Definition SwerveModule.hpp:497
ClosedLoopOutputType GetSteerClosedLoopOutputType() const
Gets the closed-loop output type to use for the steer motor.
Definition SwerveModule.hpp:459
impl::SwerveModuleImpl * _module
The underlying swerve module instance.
Definition SwerveModule.hpp:69
SwerveModuleConstants< typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration > Constants
All constants for a swerve module.
Definition SwerveModule.hpp:62
SteerMotorT const & GetSteerMotor() const
Gets this module's Steer Motor reference.
Definition SwerveModule.hpp:509
EncoderT const & GetEncoder() const
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:534
void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
Controls this module using the specified drive and steer control requests.
Definition SwerveModule.hpp:380
SwerveModuleVelocity GetTargetVelocity() const
Get the target velocity of the module.
Definition SwerveModule.hpp:431
ClosedLoopOutputType GetDriveClosedLoopOutputType() const
Gets the closed-loop output type to use for the drive motor.
Definition SwerveModule.hpp:449
EncoderT & GetEncoder()
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:522
SwerveModulePosition GetPosition(bool refresh)
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compen...
Definition SwerveModule.hpp:394
DriveMotorT & GetDriveMotor()
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:472
DriveMotorT const & GetDriveMotor() const
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:484
SwerveModule(Constants const &constants, CANBus canbus, impl::SwerveModuleImpl &module)
Construct a SwerveModule with the specified constants.
Definition SwerveModule.hpp:84
SwerveModuleVelocity GetCurrentVelocity() const
Get the current velocity of the module.
Definition SwerveModule.hpp:419
virtual void ResetPosition()
Resets this module's drive motor position to 0 rotations.
Definition SwerveModule.hpp:439
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveModule.hpp:66
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:61
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
constexpr const char * GetName() const
Gets the name of this StatusCode.
Definition StatusCodes.h:867
constexpr bool IsOK() const
Definition StatusCodes.h:860
Definition ExternalFeedbackConfigs.hpp:21
Definition ExternalFeedbackConfigs.hpp:17
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:25
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:41
Definition SwerveModule.hpp:28
ClosedLoopOutputType
Supported closed-loop output types.
Definition SwerveModuleConstants.hpp:22
@ TalonFXS_Brushed_AC
Brushed motor connected to a Talon FXS on terminals A and C.
Definition SwerveModuleConstants.hpp:77
@ TalonFXS_Brushed_AB
Brushed motor connected to a Talon FXS on terminals A and B.
Definition SwerveModuleConstants.hpp:73
@ TalonFX_Integrated
Talon FX integrated brushless motor.
Definition SwerveModuleConstants.hpp:53
@ TalonFXS_Brushed_BC
Brushed motor connected to a Talon FXS on terminals B and C.
Definition SwerveModuleConstants.hpp:81
@ TalonFXS_NEO550_JST
Third party NEO550 brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:69
@ TalonFXS_NEO_JST
Third party NEO brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:61
@ TalonFXS_VORTEX_JST
Third party VORTEX brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:65
@ TalonFXS_Minion_JST
CTR Electronics Minion® brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:57
@ FusedCANcoder
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANcoder for the steer motor.
Definition SwerveModuleConstants.hpp:92
@ SyncCANdiPWM2
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANdiPWM2 for the steer motor.
Definition SwerveModuleConstants.hpp:122
@ SyncCANdiPWM1
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANdiPWM1 for the steer motor.
Definition SwerveModuleConstants.hpp:117
@ RemoteCANdiPWM2
Use signals::FeedbackSensorSourceValue::RemoteCANdiPWM2 for the steer motor.
Definition SwerveModuleConstants.hpp:132
@ FusedCANdiPWM2
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANdiPWM2 for the steer motor.
Definition SwerveModuleConstants.hpp:112
@ FusedCANdiPWM1
Requires Pro; Use signals::FeedbackSensorSourceValue::FusedCANdiPWM1 for the steer motor.
Definition SwerveModuleConstants.hpp:107
@ RemoteCANdiPWM1
Use signals::FeedbackSensorSourceValue::RemoteCANdiPWM1 for the steer motor.
Definition SwerveModuleConstants.hpp:127
@ SyncCANcoder
Requires Pro; Use signals::FeedbackSensorSourceValue::SyncCANcoder for the steer motor.
Definition SwerveModuleConstants.hpp:97
@ TalonFXS_PulseWidth
Use signals::ExternalFeedbackSensorSourceValue::PulseWidth for the steer motor.
Definition SwerveModuleConstants.hpp:137
@ RemoteCANcoder
Use signals::FeedbackSensorSourceValue::RemoteCANcoder for the steer motor.
Definition SwerveModuleConstants.hpp:102
@ TalonFX_Integrated
Talon FX integrated brushless motor.
Definition SwerveModuleConstants.hpp:35
@ TalonFXS_NEO_JST
Third party NEO brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:39
@ TalonFXS_VORTEX_JST
Third party VORTEX brushless motor connected to a Talon FXS over JST.
Definition SwerveModuleConstants.hpp:43
Definition ExternalFeedbackConfigs.hpp:16
Definition motor_constants.h:14
static constexpr int Leads_A_and_B
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:3700
static constexpr int Leads_B_and_C
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:3724
static constexpr int Leads_A_and_C
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:3712
static constexpr int SyncCANcoder
Requires Phoenix Pro; Talon will synchronize its commutation sensor position against another CANcoder...
Definition SpnEnums.hpp:3325
static constexpr int FusedCANdiPWM2
Requires Phoenix Pro; Talon will fuse a pulse-width encoder remotely attached to the Sensor Input 2 (...
Definition SpnEnums.hpp:3374
static constexpr int SyncCANdiPWM1
Requires Phoenix Pro; Talon will synchronize its internal rotor position against the pulse-width enco...
Definition SpnEnums.hpp:3393
static constexpr int RemoteCANdiPWM1
Use a pulse-width encoder remotely attached to the Sensor Input 1 (S1IN) on CANdi™ (this also require...
Definition SpnEnums.hpp:3343
static constexpr int SyncCANdiPWM2
Requires Phoenix Pro; Talon will synchronize its internal rotor position against the pulse-width enco...
Definition SpnEnums.hpp:3405
static constexpr int RemoteCANcoder
Use another CANcoder on the same CAN bus (this also requires setting FeedbackRemoteSensorID).
Definition SpnEnums.hpp:3284
static constexpr int FusedCANdiPWM1
Requires Phoenix Pro; Talon will fuse a pulse-width encoder remotely attached to the Sensor Input 1 (...
Definition SpnEnums.hpp:3366
static constexpr int FusedCANcoder
Requires Phoenix Pro; Talon will fuse another CANcoder's information with the commutation sensor,...
Definition SpnEnums.hpp:3313
static constexpr int RemoteCANdiPWM2
Use a pulse-width encoder remotely attached to the Sensor Input 2 (S2IN) on CANdi™ (this also require...
Definition SpnEnums.hpp:3351
static constexpr int PulseWidth
Use a pulse-width encoder directly attached to the Talon data port.
Definition SpnEnums.hpp:3335
static constexpr int RemoteCANcoder
Use another CANcoder on the same CAN bus (this also requires setting FeedbackRemoteSensorID).
Definition SpnEnums.hpp:1699
static constexpr int SyncCANdiPWM2
Requires Phoenix Pro; Talon will synchronize its internal rotor position against the pulse-width enco...
Definition SpnEnums.hpp:1811
static constexpr int RemoteCANdiPWM2
Use a pulse-width encoder remotely attached to the Sensor Input 2 (S2IN) on the CTR Electronics' CANd...
Definition SpnEnums.hpp:1756
static constexpr int SyncCANdiPWM1
Requires Phoenix Pro; Talon will synchronize its internal rotor position against the pulse-width enco...
Definition SpnEnums.hpp:1799
static constexpr int SyncCANcoder
Requires Phoenix Pro; Talon will synchronize its internal rotor position against another CANcoder,...
Definition SpnEnums.hpp:1740
static constexpr int RemoteCANdiPWM1
Use a pulse-width encoder remotely attached to the Sensor Input 1 (S1IN) on the CTR Electronics' CANd...
Definition SpnEnums.hpp:1748
static constexpr int FusedCANdiPWM1
Requires Phoenix Pro; Talon will fuse a pulse-width encoder remotely attached to the Sensor Input 1 (...
Definition SpnEnums.hpp:1772
static constexpr int FusedCANcoder
Requires Phoenix Pro; Talon will fuse another CANcoder's information with the internal rotor,...
Definition SpnEnums.hpp:1728
static constexpr int FusedCANdiPWM2
Requires Phoenix Pro; Talon will fuse a pulse-width encoder remotely attached to the Sensor Input 2 (...
Definition SpnEnums.hpp:1780
static constexpr int CounterClockwise_Positive
Positive motor output results in counter-clockwise motion.
Definition SpnEnums.hpp:1554
static constexpr int Clockwise_Positive
Positive motor output results in clockwise motion.
Definition SpnEnums.hpp:1558
static constexpr int NEO_JST
Third party NEO brushless three phase motor (~6000 RPM at 12V).
Definition SpnEnums.hpp:2883
static constexpr int NEO550_JST
Third party NEO550 brushless three phase motor (~11000 RPM at 12V).
Definition SpnEnums.hpp:2895
static constexpr int Brushed_DC
Third party brushed DC motor with two leads.
Definition SpnEnums.hpp:2871
static constexpr int Minion_JST
CTR Electronics Minion® brushless three phase motor.
Definition SpnEnums.hpp:2859
static constexpr int VORTEX_JST
Third party VORTEX brushless three phase motor.
Definition SpnEnums.hpp:2907
static constexpr int Brake
Definition SpnEnums.hpp:1607
static constexpr int CounterClockwise_Positive
Counter-clockwise motion reports positive rotation.
Definition SpnEnums.hpp:201
static constexpr int Clockwise_Positive
Clockwise motion reports positive rotation.
Definition SpnEnums.hpp:205
static constexpr int Aligned
The sensor direction is normally aligned with the motor.
Definition SpnEnums.hpp:3481
static constexpr int Opposed
The sensor direction is normally opposed to the motor.
Definition SpnEnums.hpp:3485
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148
bool DriveMotorInverted
True if the drive motor is inverted.
Definition SwerveModuleConstants.hpp:180
wpi::units::scalar_t SteerMotorGearRatio
Gear ratio between the steer motor and the azimuth encoder.
Definition SwerveModuleConstants.hpp:201
SteerMotorArrangement SteerMotorType
Choose the motor used for the steer motor.
Definition SwerveModuleConstants.hpp:266
DriveMotorConfigsT DriveMotorInitialConfigs
The initial configs used to configure the drive motor of the swerve module.
Definition SwerveModuleConstants.hpp:302
configs::Slot0Configs DriveMotorGains
The drive motor closed-loop gains.
Definition SwerveModuleConstants.hpp:231
wpi::units::ampere_t SlipCurrent
The maximum amount of stator current the drive motors can apply without slippage.
Definition SwerveModuleConstants.hpp:244
configs::Slot0Configs SteerMotorGains
The steer motor closed-loop gains.
Definition SwerveModuleConstants.hpp:222
SteerFeedbackType FeedbackSource
Choose how the feedback sensors should be configured.
Definition SwerveModuleConstants.hpp:279
int EncoderId
CAN ID of the absolute encoder used for azimuth.
Definition SwerveModuleConstants.hpp:162
DriveMotorArrangement DriveMotorType
Choose the motor used for the drive motor.
Definition SwerveModuleConstants.hpp:259
bool EncoderInverted
True if the azimuth encoder is inverted from the azimuth.
Definition SwerveModuleConstants.hpp:192
SteerMotorConfigsT SteerMotorInitialConfigs
The initial configs used to configure the steer motor of the swerve module.
Definition SwerveModuleConstants.hpp:326
EncoderConfigsT EncoderInitialConfigs
The initial configs used to configure the azimuth encoder of the swerve module.
Definition SwerveModuleConstants.hpp:342
wpi::units::turn_t EncoderOffset
Offset of the azimuth encoder.
Definition SwerveModuleConstants.hpp:166
bool SteerMotorInverted
True if the steer motor is inverted from the azimuth.
Definition SwerveModuleConstants.hpp:186
Contains everything the swerve module needs to apply a request.
Definition SwerveModuleImpl.hpp:66