CTRE Phoenix 6 C++ 26.1.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 {
22 class CANcoderConfiguration;
23 class CANdiConfiguration;
24 class TalonFXConfiguration;
25 class TalonFXSConfiguration;
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
59protected:
60 /** \brief Number of times to attempt config applies. */
61 static constexpr int kNumConfigAttempts = 2;
62
63 /** \brief The underlying swerve module instance. */
65
66private:
67 DriveMotorT _driveMotor;
68 SteerMotorT _steerMotor;
69 EncoderT _encoder;
70
71public:
72 /**
73 * \brief Construct a SwerveModule with the specified constants.
74 *
75 * \param constants Constants used to construct the module
76 * \param canbus The CAN bus this module is on
77 * \param module The impl#SwerveModuleImpl to use
78 */
81 CANBus canbus,
83 ) :
84 _module{&module},
85 _driveMotor{constants.DriveMotorId, canbus},
86 _steerMotor{constants.SteerMotorId, canbus},
87 _encoder{constants.EncoderId, canbus}
88 {
90
91 typename DriveMotorT::Configuration driveConfigs = constants.DriveMotorInitialConfigs;
92 driveConfigs.MotorOutput.NeutralMode = signals::NeutralModeValue::Brake;
93
94 driveConfigs.Slot0 = constants.DriveMotorGains;
95 if constexpr (!std::same_as<configs::TalonFXSConfiguration, decltype(driveConfigs)>) {
96 driveConfigs.TorqueCurrent.PeakForwardTorqueCurrent = constants.SlipCurrent;
97 driveConfigs.TorqueCurrent.PeakReverseTorqueCurrent = -constants.SlipCurrent;
98 }
99 driveConfigs.CurrentLimits.StatorCurrentLimit = constants.SlipCurrent;
100 driveConfigs.CurrentLimits.StatorCurrentLimitEnable = true;
101
102 if constexpr (std::same_as<configs::TalonFXSConfiguration, decltype(driveConfigs)>) {
103 driveConfigs.ExternalFeedback.RotorToSensorRatio = 1.0;
104 driveConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
105
106 switch (constants.DriveMotorType) {
108 printf(
109 "Cannot use TalonFX_Integrated drive motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
110 GetDriveMotor().GetDeviceID()
111 );
112 break;
113
115 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
116 break;
118 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
119 break;
120 }
121 } else {
122 driveConfigs.Feedback.RotorToSensorRatio = 1.0;
123 driveConfigs.Feedback.SensorToMechanismRatio = 1.0;
124
126 printf("Drive motor Talon FX ID %d only supports TalonFX_Integrated.", GetDriveMotor().GetDeviceID());
127 }
128 }
129
130 driveConfigs.MotorOutput.Inverted = constants.DriveMotorInverted ? signals::InvertedValue::Clockwise_Positive
132 for (int i = 0; i < kNumConfigAttempts; ++i) {
133 response = GetDriveMotor().GetConfigurator().Apply(driveConfigs);
134 if (response.IsOK()) break;
135 }
136 if (!response.IsOK()) {
137 printf("Talon ID %d failed config with error %s\n", GetDriveMotor().GetDeviceID(), response.GetName());
138 }
139
140 typename SteerMotorT::Configuration steerConfigs = constants.SteerMotorInitialConfigs;
141 steerConfigs.MotorOutput.NeutralMode = signals::NeutralModeValue::Brake;
142
143 steerConfigs.Slot0 = constants.SteerMotorGains;
144
145 if constexpr (std::same_as<configs::TalonFXSConfiguration, decltype(steerConfigs)>) {
146 switch (constants.SteerMotorType) {
148 printf(
149 "Cannot use TalonFX_Integrated steer motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
150 GetSteerMotor().GetDeviceID()
151 );
152 break;
153
155 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Minion_JST;
156 break;
158 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
159 break;
161 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
162 break;
164 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO550_JST;
165 break;
167 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
168 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_B;
169 break;
171 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
172 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_C;
173 break;
175 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
176 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_B_and_C;
177 break;
178 }
179
180 /* Modify configuration to use remote encoder setting */
181 steerConfigs.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId;
182 switch (constants.FeedbackSource) {
184 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANcoder;
185 break;
187 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANcoder;
188 break;
190 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANcoder;
191 break;
192
194 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM1;
195 break;
197 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM2;
198 break;
200 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM1;
201 break;
203 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM2;
204 break;
206 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM1;
207 break;
209 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM2;
210 break;
211
213 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::PulseWidth;
214 steerConfigs.ExternalFeedback.AbsoluteSensorOffset = constants.EncoderOffset;
215 steerConfigs.ExternalFeedback.SensorPhase = constants.EncoderInverted
218 break;
219 }
220 steerConfigs.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
221 steerConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
222 } else {
224 printf("Steer motor Talon FX ID %d only supports TalonFX_Integrated.", GetSteerMotor().GetDeviceID());
225 }
226
227 /* Modify configuration to use remote encoder setting */
228 steerConfigs.Feedback.FeedbackRemoteSensorID = constants.EncoderId;
229 switch (constants.FeedbackSource) {
231 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANcoder;
232 break;
234 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANcoder;
235 break;
237 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANcoder;
238 break;
239
241 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM1;
242 break;
244 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM2;
245 break;
247 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM1;
248 break;
250 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM2;
251 break;
253 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM1;
254 break;
256 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM2;
257 break;
258
260 printf(
261 "Cannot use Pulse Width steer feedback type on Talon FX ID %d. Pulse Width is only supported on Talon FXS.\n",
262 GetSteerMotor().GetDeviceID()
263 );
264 break;
265 }
266 steerConfigs.Feedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
267 steerConfigs.Feedback.SensorToMechanismRatio = 1.0;
268 }
269
270 steerConfigs.MotionMagic.MotionMagicExpo_kV = 0.12_V / 1_tps * constants.SteerMotorGearRatio;
271 steerConfigs.MotionMagic.MotionMagicExpo_kA = 1.2_V / 1_tr_per_s_sq / constants.SteerMotorGearRatio;
272
273 steerConfigs.ClosedLoopGeneral.ContinuousWrap = true; // Enable continuous wrap for swerve modules
274
275 steerConfigs.MotorOutput.Inverted = constants.SteerMotorInverted
278 for (int i = 0; i < kNumConfigAttempts; ++i) {
279 response = GetSteerMotor().GetConfigurator().Apply(steerConfigs);
280 if (response.IsOK()) break;
281 }
282 if (!response.IsOK()) {
283 printf("Talon ID %d failed config with error %s\n", GetSteerMotor().GetDeviceID(), response.GetName());
284 }
285
286 typename EncoderT::Configuration encoderConfigs = constants.EncoderInitialConfigs;
287 if constexpr (std::same_as<configs::CANcoderConfiguration, decltype(encoderConfigs)>) {
288 encoderConfigs.MagnetSensor.MagnetOffset = constants.EncoderOffset;
289 encoderConfigs.MagnetSensor.SensorDirection = constants.EncoderInverted
292
293 for (int i = 0; i < kNumConfigAttempts; ++i) {
294 response = GetEncoder().GetConfigurator().Apply(encoderConfigs);
295 if (response.IsOK()) break;
296 }
297 if (!response.IsOK()) {
298 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
299 }
300 } else if constexpr (std::same_as<configs::CANdiConfiguration, decltype(encoderConfigs)>) {
301 for (int i = 0; i < kNumConfigAttempts; ++i) {
302 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.DigitalInputs);
303 if (response.IsOK()) break;
304 }
305 if (!response.IsOK()) {
306 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
307 }
308
309 for (int i = 0; i < kNumConfigAttempts; ++i) {
310 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.CustomParams);
311 if (response.IsOK()) break;
312 }
313 if (!response.IsOK()) {
314 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
315 }
316
317 switch (constants.FeedbackSource) {
321 encoderConfigs.PWM1.AbsoluteSensorOffset = constants.EncoderOffset;
322 encoderConfigs.PWM1.SensorDirection = constants.EncoderInverted;
323
324 for (int i = 0; i < kNumConfigAttempts; ++i) {
325 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM1);
326 if (response.IsOK()) break;
327 }
328 if (!response.IsOK()) {
329 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
330 }
331 break;
332
336 encoderConfigs.PWM2.AbsoluteSensorOffset = constants.EncoderOffset;
337 encoderConfigs.PWM2.SensorDirection = constants.EncoderInverted;
338
339 for (int i = 0; i < kNumConfigAttempts; ++i) {
340 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM2);
341 if (response.IsOK()) break;
342 }
343 if (!response.IsOK()) {
344 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
345 }
346 break;
347
348 default:
349 break;
350 }
351 }
352 }
353
354 virtual ~SwerveModule() = default;
355
356 /**
357 * \brief Applies the desired ModuleRequest to this module.
358 *
359 * \param moduleRequest The request to apply to this module
360 */
361 virtual void Apply(ModuleRequest const &moduleRequest)
362 {
363 return _module->Apply(moduleRequest);
364 }
365
366 /**
367 * \brief Controls this module using the specified drive and steer control requests.
368 *
369 * This is intended only to be used for characterization of the robot; do not use this for normal use.
370 *
371 * \param driveRequest The control request to apply to the drive motor
372 * \param steerRequest The control request to apply to the steer motor
373 */
374 template <
375 std::derived_from<controls::ControlRequest> DriveReq,
376 std::derived_from<controls::ControlRequest> SteerReq
377 >
378 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
379 {
380 return _module->Apply(std::forward<DriveReq>(driveRequest), std::forward<SteerReq>(steerRequest));
381 }
382
383 /**
384 * \brief Gets the state of this module and passes it back as a
385 * SwerveModulePosition object with latency compensated values.
386 *
387 * This function is blocking when it performs a refresh.
388 *
389 * \param refresh True if the signals should be refreshed
390 * \returns SwerveModulePosition containing this module's state.
391 */
392 SwerveModulePosition GetPosition(bool refresh)
393 {
394 return _module->GetPosition(refresh);
395 }
396
397 /**
398 * \brief Gets the last cached swerve module position.
399 * This differs from #GetPosition in that it will not
400 * perform any latency compensation or refresh the signals.
401 *
402 * \returns Last cached SwerveModulePosition
403 */
404 SwerveModulePosition GetCachedPosition() const
405 {
406 return _module->GetCachedPosition();
407 }
408
409 /**
410 * \brief Get the current state of the module.
411 *
412 * This is typically used for telemetry, as the SwerveModulePosition
413 * is used for odometry.
414 *
415 * \returns Current state of the module
416 */
417 SwerveModuleState GetCurrentState() const
418 {
419 return _module->GetCurrentState();
420 }
421
422 /**
423 * \brief Get the target state of the module.
424 *
425 * This is typically used for telemetry.
426 *
427 * \returns Target state of the module
428 */
429 SwerveModuleState GetTargetState() const
430 {
431 return _module->GetTargetState();
432 }
433
434 /**
435 * \brief Resets this module's drive motor position to 0 rotations.
436 */
437 virtual void ResetPosition()
438 {
439 return _module->ResetPosition();
440 }
441
442 /**
443 * \brief Gets the closed-loop output type to use for the drive motor.
444 *
445 * \returns Drive motor closed-loop output type
446 */
451
452 /**
453 * \brief Gets the closed-loop output type to use for the steer motor.
454 *
455 * \returns Steer motor closed-loop output type
456 */
461
462 /**
463 * \brief Gets this module's Drive Motor reference.
464 *
465 * This should be used only to access signals and change configurations that the
466 * swerve drivetrain does not configure itself.
467 *
468 * \returns This module's Drive Motor reference
469 */
470 DriveMotorT &GetDriveMotor()
471 {
472 return _driveMotor;
473 }
474 /**
475 * \brief Gets this module's Drive Motor reference.
476 *
477 * This should be used only to access signals and change configurations that the
478 * swerve drivetrain does not configure itself.
479 *
480 * \returns This module's Drive Motor reference
481 */
482 DriveMotorT const &GetDriveMotor() const
483 {
484 return _driveMotor;
485 }
486
487 /**
488 * \brief Gets this module's Steer Motor reference.
489 *
490 * This should be used only to access signals and change configurations that the
491 * swerve drivetrain does not configure itself.
492 *
493 * \returns This module's Steer Motor reference
494 */
495 SteerMotorT &GetSteerMotor()
496 {
497 return _steerMotor;
498 }
499 /**
500 * \brief Gets this module's Steer Motor reference.
501 *
502 * This should be used only to access signals and change configurations that the
503 * swerve drivetrain does not configure itself.
504 *
505 * \returns This module's Steer Motor reference
506 */
507 SteerMotorT const &GetSteerMotor() const
508 {
509 return _steerMotor;
510 }
511
512 /**
513 * \brief Gets this module's azimuth encoder reference.
514 *
515 * This should be used only to access signals and change configurations that the
516 * swerve drivetrain does not configure itself.
517 *
518 * \returns This module's azimuth encoder reference
519 */
520 EncoderT &GetEncoder()
521 {
522 return _encoder;
523 }
524 /**
525 * \brief Gets this module's azimuth encoder reference.
526 *
527 * This should be used only to access signals and change configurations that the
528 * swerve drivetrain does not configure itself.
529 *
530 * \returns This module's azimuth encoder reference
531 */
532 EncoderT const &GetEncoder() const
533 {
534 return _encoder;
535 }
536};
537
538}
539}
540}
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 FXS motor controller.
Definition CoreTalonFXS.hpp:133
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModule.hpp:52
virtual void Apply(ModuleRequest const &moduleRequest)
Applies the desired ModuleRequest to this module.
Definition SwerveModule.hpp:361
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModule.hpp:404
SteerMotorT & GetSteerMotor()
Gets this module's Steer Motor reference.
Definition SwerveModule.hpp:495
ClosedLoopOutputType GetSteerClosedLoopOutputType() const
Gets the closed-loop output type to use for the steer motor.
Definition SwerveModule.hpp:457
impl::SwerveModuleImpl * _module
The underlying swerve module instance.
Definition SwerveModule.hpp:64
SteerMotorT const & GetSteerMotor() const
Gets this module's Steer Motor reference.
Definition SwerveModule.hpp:507
EncoderT const & GetEncoder() const
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:532
void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
Controls this module using the specified drive and steer control requests.
Definition SwerveModule.hpp:378
SwerveModuleState GetCurrentState() const
Get the current state of the module.
Definition SwerveModule.hpp:417
ClosedLoopOutputType GetDriveClosedLoopOutputType() const
Gets the closed-loop output type to use for the drive motor.
Definition SwerveModule.hpp:447
EncoderT & GetEncoder()
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:520
SwerveModuleState GetTargetState() const
Get the target state of the module.
Definition SwerveModule.hpp:429
SwerveModule(SwerveModuleConstants< typename DriveMotorT::Configuration, typename SteerMotorT::Configuration, typename EncoderT::Configuration > const &constants, CANBus canbus, impl::SwerveModuleImpl &module)
Construct a SwerveModule with the specified constants.
Definition SwerveModule.hpp:79
SwerveModulePosition GetPosition(bool refresh)
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compen...
Definition SwerveModule.hpp:392
DriveMotorT & GetDriveMotor()
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:470
DriveMotorT const & GetDriveMotor() const
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:482
virtual void ResetPosition()
Resets this module's drive motor position to 0 rotations.
Definition SwerveModule.hpp:437
static constexpr int kNumConfigAttempts
Number of times to attempt config applies.
Definition SwerveModule.hpp:61
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:61
SwerveModuleState GetCurrentState() const
Get the current state of the module.
Definition SwerveModuleImpl.hpp:361
ClosedLoopOutputType GetSteerClosedLoopOutputType() const
Gets the closed-loop output type to use for the steer motor.
Definition SwerveModuleImpl.hpp:399
SwerveModuleState GetTargetState() const
Get the target state of the module.
Definition SwerveModuleImpl.hpp:373
void Apply(ModuleRequest const &moduleRequest)
Applies the desired ModuleRequest to this module.
ClosedLoopOutputType GetDriveClosedLoopOutputType() const
Gets the closed-loop output type to use for the drive motor.
Definition SwerveModuleImpl.hpp:389
SwerveModulePosition GetPosition(bool refresh)
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compen...
void ResetPosition()
Resets this module's drive motor position to 0 rotations.
Definition SwerveModuleImpl.hpp:378
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModuleImpl.hpp:351
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:28
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
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.
@ 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_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.
@ TalonFXS_Minion_JST
CTR Electronics Minion® brushless motor connected to a Talon FXS over JST.
@ 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.
@ 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.
@ CANcoder
Definition FrcUsageReport.hpp:23
@ TalonFXS
Definition FrcUsageReport.hpp:28
@ TalonFX
Definition FrcUsageReport.hpp:24
@ CANdi
Definition FrcUsageReport.hpp:29
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
SteerMotorArrangement SteerMotorType
Choose the motor used for the steer motor.
Definition SwerveModuleConstants.hpp:265
DriveMotorConfigsT DriveMotorInitialConfigs
The initial configs used to configure the drive motor of the swerve module.
Definition SwerveModuleConstants.hpp:301
units::current::ampere_t SlipCurrent
The maximum amount of stator current the drive motors can apply without slippage.
Definition SwerveModuleConstants.hpp:244
units::dimensionless::scalar_t SteerMotorGearRatio
Gear ratio between the steer motor and the azimuth encoder.
Definition SwerveModuleConstants.hpp:201
configs::Slot0Configs DriveMotorGains
The drive motor closed-loop gains.
Definition SwerveModuleConstants.hpp:231
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:278
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:258
bool EncoderInverted
True if the azimuth encoder is inverted from the azimuth.
Definition SwerveModuleConstants.hpp:192
SteerMotorConfigsT SteerMotorInitialConfigs
The initial configs used to configure the steer motor of the swerve module.
Definition SwerveModuleConstants.hpp:325
units::angle::turn_t EncoderOffset
Offset of the azimuth encoder.
Definition SwerveModuleConstants.hpp:166
EncoderConfigsT EncoderInitialConfigs
The initial configs used to configure the azimuth encoder of the swerve module.
Definition SwerveModuleConstants.hpp:341
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