CTRE Phoenix 6 C++ 26.0.0-beta-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 switch (constants.DriveMotorType) {
105 printf(
106 "Cannot use TalonFX_Integrated drive motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
107 GetDriveMotor().GetDeviceID()
108 );
109 break;
110
112 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
113 break;
115 driveConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
116 break;
117 }
118 } else {
120 printf("Drive motor Talon FX ID %d only supports TalonFX_Integrated.", GetDriveMotor().GetDeviceID());
121 }
122 }
123
124 driveConfigs.MotorOutput.Inverted = constants.DriveMotorInverted ? signals::InvertedValue::Clockwise_Positive
126 for (int i = 0; i < kNumConfigAttempts; ++i) {
127 response = GetDriveMotor().GetConfigurator().Apply(driveConfigs);
128 if (response.IsOK()) break;
129 }
130 if (!response.IsOK()) {
131 printf("Talon ID %d failed config with error %s\n", GetDriveMotor().GetDeviceID(), response.GetName());
132 }
133
134 typename SteerMotorT::Configuration steerConfigs = constants.SteerMotorInitialConfigs;
135 steerConfigs.MotorOutput.NeutralMode = signals::NeutralModeValue::Brake;
136
137 steerConfigs.Slot0 = constants.SteerMotorGains;
138
139 if constexpr (std::same_as<configs::TalonFXSConfiguration, decltype(steerConfigs)>) {
140 switch (constants.SteerMotorType) {
142 printf(
143 "Cannot use TalonFX_Integrated steer motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
144 GetSteerMotor().GetDeviceID()
145 );
146 break;
147
149 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Minion_JST;
150 break;
152 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO_JST;
153 break;
155 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::VORTEX_JST;
156 break;
158 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::NEO550_JST;
159 break;
161 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
162 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_B;
163 break;
165 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
166 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_A_and_C;
167 break;
169 steerConfigs.Commutation.MotorArrangement = signals::MotorArrangementValue::Brushed_DC;
170 steerConfigs.Commutation.BrushedMotorWiring = signals::BrushedMotorWiringValue::Leads_B_and_C;
171 break;
172 }
173
174 /* Modify configuration to use remote encoder setting */
175 steerConfigs.ExternalFeedback.FeedbackRemoteSensorID = constants.EncoderId;
176 switch (constants.FeedbackSource) {
178 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANcoder;
179 break;
181 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANcoder;
182 break;
184 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANcoder;
185 break;
186
188 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM1;
189 break;
191 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::FusedCANdiPWM2;
192 break;
194 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM1;
195 break;
197 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::SyncCANdiPWM2;
198 break;
200 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM1;
201 break;
203 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::RemoteCANdiPWM2;
204 break;
205
207 steerConfigs.ExternalFeedback.ExternalFeedbackSensorSource = signals::ExternalFeedbackSensorSourceValue::PulseWidth;
208 steerConfigs.ExternalFeedback.AbsoluteSensorOffset = constants.EncoderOffset;
209 steerConfigs.ExternalFeedback.SensorPhase = constants.EncoderInverted
212 break;
213 }
214 steerConfigs.ExternalFeedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
215 } else {
217 printf("Steer motor Talon FX ID %d only supports TalonFX_Integrated.", GetSteerMotor().GetDeviceID());
218 }
219
220 /* Modify configuration to use remote encoder setting */
221 steerConfigs.Feedback.FeedbackRemoteSensorID = constants.EncoderId;
222 switch (constants.FeedbackSource) {
224 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANcoder;
225 break;
227 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANcoder;
228 break;
230 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANcoder;
231 break;
232
234 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM1;
235 break;
237 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::FusedCANdiPWM2;
238 break;
240 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM1;
241 break;
243 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::SyncCANdiPWM2;
244 break;
246 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM1;
247 break;
249 steerConfigs.Feedback.FeedbackSensorSource = signals::FeedbackSensorSourceValue::RemoteCANdiPWM2;
250 break;
251
253 printf(
254 "Cannot use Pulse Width steer feedback type on Talon FX ID %d. Pulse Width is only supported on Talon FXS.\n",
255 GetSteerMotor().GetDeviceID()
256 );
257 break;
258 }
259 steerConfigs.Feedback.RotorToSensorRatio = constants.SteerMotorGearRatio;
260 }
261
262 steerConfigs.MotionMagic.MotionMagicExpo_kV = 0.12_V / 1_tps * constants.SteerMotorGearRatio;
263 steerConfigs.MotionMagic.MotionMagicExpo_kA = 0.8_V / 1_tr_per_s_sq / constants.SteerMotorGearRatio;
264
265 steerConfigs.ClosedLoopGeneral.ContinuousWrap = true; // Enable continuous wrap for swerve modules
266
267 steerConfigs.MotorOutput.Inverted = constants.SteerMotorInverted
270 for (int i = 0; i < kNumConfigAttempts; ++i) {
271 response = GetSteerMotor().GetConfigurator().Apply(steerConfigs);
272 if (response.IsOK()) break;
273 }
274 if (!response.IsOK()) {
275 printf("Talon ID %d failed config with error %s\n", GetSteerMotor().GetDeviceID(), response.GetName());
276 }
277
278 typename EncoderT::Configuration encoderConfigs = constants.EncoderInitialConfigs;
279 if constexpr (std::same_as<configs::CANcoderConfiguration, decltype(encoderConfigs)>) {
280 encoderConfigs.MagnetSensor.MagnetOffset = constants.EncoderOffset;
281 encoderConfigs.MagnetSensor.SensorDirection = constants.EncoderInverted
284
285 for (int i = 0; i < kNumConfigAttempts; ++i) {
286 response = GetEncoder().GetConfigurator().Apply(encoderConfigs);
287 if (response.IsOK()) break;
288 }
289 if (!response.IsOK()) {
290 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
291 }
292 } else if constexpr (std::same_as<configs::CANdiConfiguration, decltype(encoderConfigs)>) {
293 for (int i = 0; i < kNumConfigAttempts; ++i) {
294 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.DigitalInputs);
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
301 for (int i = 0; i < kNumConfigAttempts; ++i) {
302 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.CustomParams);
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 switch (constants.FeedbackSource) {
313 encoderConfigs.PWM1.AbsoluteSensorOffset = constants.EncoderOffset;
314 encoderConfigs.PWM1.SensorDirection = constants.EncoderInverted;
315
316 for (int i = 0; i < kNumConfigAttempts; ++i) {
317 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM1);
318 if (response.IsOK()) break;
319 }
320 if (!response.IsOK()) {
321 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
322 }
323 break;
324
328 encoderConfigs.PWM2.AbsoluteSensorOffset = constants.EncoderOffset;
329 encoderConfigs.PWM2.SensorDirection = constants.EncoderInverted;
330
331 for (int i = 0; i < kNumConfigAttempts; ++i) {
332 response = GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM2);
333 if (response.IsOK()) break;
334 }
335 if (!response.IsOK()) {
336 printf("Encoder ID %d failed config with error %s\n", GetEncoder().GetDeviceID(), response.GetName());
337 }
338 break;
339
340 default:
341 break;
342 }
343 }
344 }
345
346 virtual ~SwerveModule() = default;
347
348 /**
349 * \brief Applies the desired ModuleRequest to this module.
350 *
351 * \param moduleRequest The request to apply to this module
352 */
353 virtual void Apply(ModuleRequest const &moduleRequest)
354 {
355 return _module->Apply(moduleRequest);
356 }
357
358 /**
359 * \brief Controls this module using the specified drive and steer control requests.
360 *
361 * This is intended only to be used for characterization of the robot; do not use this for normal use.
362 *
363 * \param driveRequest The control request to apply to the drive motor
364 * \param steerRequest The control request to apply to the steer motor
365 */
366 template <
367 std::derived_from<controls::ControlRequest> DriveReq,
368 std::derived_from<controls::ControlRequest> SteerReq
369 >
370 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
371 {
372 return _module->Apply(std::forward<DriveReq>(driveRequest), std::forward<SteerReq>(steerRequest));
373 }
374
375 /**
376 * \brief Gets the state of this module and passes it back as a
377 * SwerveModulePosition object with latency compensated values.
378 *
379 * This function is blocking when it performs a refresh.
380 *
381 * \param refresh True if the signals should be refreshed
382 * \returns SwerveModulePosition containing this module's state.
383 */
384 SwerveModulePosition GetPosition(bool refresh)
385 {
386 return _module->GetPosition(refresh);
387 }
388
389 /**
390 * \brief Gets the last cached swerve module position.
391 * This differs from #GetPosition in that it will not
392 * perform any latency compensation or refresh the signals.
393 *
394 * \returns Last cached SwerveModulePosition
395 */
396 SwerveModulePosition GetCachedPosition() const
397 {
398 return _module->GetCachedPosition();
399 }
400
401 /**
402 * \brief Get the current state of the module.
403 *
404 * This is typically used for telemetry, as the SwerveModulePosition
405 * is used for odometry.
406 *
407 * \returns Current state of the module
408 */
409 SwerveModuleState GetCurrentState() const
410 {
411 return _module->GetCurrentState();
412 }
413
414 /**
415 * \brief Get the target state of the module.
416 *
417 * This is typically used for telemetry.
418 *
419 * \returns Target state of the module
420 */
421 SwerveModuleState GetTargetState() const
422 {
423 return _module->GetTargetState();
424 }
425
426 /**
427 * \brief Resets this module's drive motor position to 0 rotations.
428 */
429 virtual void ResetPosition()
430 {
431 return _module->ResetPosition();
432 }
433
434 /**
435 * \brief Gets the closed-loop output type to use for the drive motor.
436 *
437 * \returns Drive motor closed-loop output type
438 */
443
444 /**
445 * \brief Gets the closed-loop output type to use for the steer motor.
446 *
447 * \returns Steer motor closed-loop output type
448 */
453
454 /**
455 * \brief Gets this module's Drive Motor reference.
456 *
457 * This should be used only to access signals and change configurations that the
458 * swerve drivetrain does not configure itself.
459 *
460 * \returns This module's Drive Motor reference
461 */
462 DriveMotorT &GetDriveMotor()
463 {
464 return _driveMotor;
465 }
466 /**
467 * \brief Gets this module's Drive Motor reference.
468 *
469 * This should be used only to access signals and change configurations that the
470 * swerve drivetrain does not configure itself.
471 *
472 * \returns This module's Drive Motor reference
473 */
474 DriveMotorT const &GetDriveMotor() const
475 {
476 return _driveMotor;
477 }
478
479 /**
480 * \brief Gets this module's Steer Motor reference.
481 *
482 * This should be used only to access signals and change configurations that the
483 * swerve drivetrain does not configure itself.
484 *
485 * \returns This module's Steer Motor reference
486 */
487 SteerMotorT &GetSteerMotor()
488 {
489 return _steerMotor;
490 }
491 /**
492 * \brief Gets this module's Steer Motor reference.
493 *
494 * This should be used only to access signals and change configurations that the
495 * swerve drivetrain does not configure itself.
496 *
497 * \returns This module's Steer Motor reference
498 */
499 SteerMotorT const &GetSteerMotor() const
500 {
501 return _steerMotor;
502 }
503
504 /**
505 * \brief Gets this module's azimuth encoder reference.
506 *
507 * This should be used only to access signals and change configurations that the
508 * swerve drivetrain does not configure itself.
509 *
510 * \returns This module's azimuth encoder reference
511 */
512 EncoderT &GetEncoder()
513 {
514 return _encoder;
515 }
516 /**
517 * \brief Gets this module's azimuth encoder reference.
518 *
519 * This should be used only to access signals and change configurations that the
520 * swerve drivetrain does not configure itself.
521 *
522 * \returns This module's azimuth encoder reference
523 */
524 EncoderT const &GetEncoder() const
525 {
526 return _encoder;
527 }
528};
529
530}
531}
532}
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:353
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModule.hpp:396
SteerMotorT & GetSteerMotor()
Gets this module's Steer Motor reference.
Definition SwerveModule.hpp:487
ClosedLoopOutputType GetSteerClosedLoopOutputType() const
Gets the closed-loop output type to use for the steer motor.
Definition SwerveModule.hpp:449
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:499
EncoderT const & GetEncoder() const
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:524
void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
Controls this module using the specified drive and steer control requests.
Definition SwerveModule.hpp:370
SwerveModuleState GetCurrentState() const
Get the current state of the module.
Definition SwerveModule.hpp:409
ClosedLoopOutputType GetDriveClosedLoopOutputType() const
Gets the closed-loop output type to use for the drive motor.
Definition SwerveModule.hpp:439
EncoderT & GetEncoder()
Gets this module's azimuth encoder reference.
Definition SwerveModule.hpp:512
SwerveModuleState GetTargetState() const
Get the target state of the module.
Definition SwerveModule.hpp:421
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:384
DriveMotorT & GetDriveMotor()
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:462
DriveMotorT const & GetDriveMotor() const
Gets this module's Drive Motor reference.
Definition SwerveModule.hpp:474
virtual void ResetPosition()
Resets this module's drive motor position to 0 rotations.
Definition SwerveModule.hpp:429
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:299
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:322
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:338
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