45 std::derived_from<hardware::traits::CommonTalon> DriveMotorT,
46 std::derived_from<hardware::traits::CommonTalon> SteerMotorT,
49 requires std::same_as<EncoderT, hardware::CANcoder> ||
50 std::same_as<EncoderT, hardware::CANdi> ||
51 std::same_as<EncoderT, hardware::TalonFXS>
72 DriveMotorT _driveMotor;
73 SteerMotorT _steerMotor;
86 _driveMotor{constants.DriveMotorId, canbus},
87 _steerMotor{constants.SteerMotorId, canbus},
88 _encoder{constants.EncoderId, canbus}
97 driveConfigs.TorqueCurrent.PeakForwardTorqueCurrent = constants.
SlipCurrent;
98 driveConfigs.TorqueCurrent.PeakReverseTorqueCurrent = -constants.
SlipCurrent;
100 driveConfigs.CurrentLimits.StatorCurrentLimit = constants.
SlipCurrent;
101 driveConfigs.CurrentLimits.StatorCurrentLimitEnable =
true;
104 driveConfigs.ExternalFeedback.RotorToSensorRatio = 1.0;
105 driveConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
110 "Cannot use TalonFX_Integrated drive motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
123 driveConfigs.Feedback.RotorToSensorRatio = 1.0;
124 driveConfigs.Feedback.SensorToMechanismRatio = 1.0;
127 printf(
"Drive motor Talon FX ID %d only supports TalonFX_Integrated.",
GetDriveMotor().GetDeviceID());
135 response =
GetDriveMotor().GetConfigurator().Apply(driveConfigs);
136 if (response.
IsOK())
break;
138 if (!response.
IsOK()) {
139 printf(
"Talon ID %d failed config with error %s\n",
GetDriveMotor().GetDeviceID(), response.
GetName());
151 "Cannot use TalonFX_Integrated steer motor type on Talon FXS ID %d. TalonFX_Integrated is only supported on Talon FX.",
183 steerConfigs.ExternalFeedback.FeedbackRemoteSensorID = constants.
EncoderId;
216 steerConfigs.ExternalFeedback.AbsoluteSensorOffset = constants.
EncoderOffset;
223 steerConfigs.ExternalFeedback.SensorToMechanismRatio = 1.0;
226 printf(
"Steer motor Talon FX ID %d only supports TalonFX_Integrated.",
GetSteerMotor().GetDeviceID());
230 steerConfigs.Feedback.FeedbackRemoteSensorID = constants.
EncoderId;
263 "Cannot use Pulse Width steer feedback type on Talon FX ID %d. Pulse Width is only supported on Talon FXS.\n",
269 steerConfigs.Feedback.SensorToMechanismRatio = 1.0;
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;
275 steerConfigs.ClosedLoopGeneral.ContinuousWrap =
true;
281 response =
GetSteerMotor().GetConfigurator().Apply(steerConfigs);
282 if (response.
IsOK())
break;
284 if (!response.
IsOK()) {
285 printf(
"Talon ID %d failed config with error %s\n",
GetSteerMotor().GetDeviceID(), response.
GetName());
290 encoderConfigs.MagnetSensor.MagnetOffset = constants.
EncoderOffset;
291 encoderConfigs.MagnetSensor.SensorDirection = constants.
EncoderInverted
296 response =
GetEncoder().GetConfigurator().Apply(encoderConfigs);
297 if (response.
IsOK())
break;
299 if (!response.
IsOK()) {
300 printf(
"Encoder ID %d failed config with error %s\n",
GetEncoder().GetDeviceID(), response.
GetName());
304 response =
GetEncoder().GetConfigurator().Apply(encoderConfigs.DigitalInputs);
305 if (response.
IsOK())
break;
307 if (!response.
IsOK()) {
308 printf(
"Encoder ID %d failed config with error %s\n",
GetEncoder().GetDeviceID(), response.
GetName());
312 response =
GetEncoder().GetConfigurator().Apply(encoderConfigs.CustomParams);
313 if (response.
IsOK())
break;
315 if (!response.
IsOK()) {
316 printf(
"Encoder ID %d failed config with error %s\n",
GetEncoder().GetDeviceID(), response.
GetName());
323 encoderConfigs.PWM1.AbsoluteSensorOffset = constants.
EncoderOffset;
327 response =
GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM1);
328 if (response.
IsOK())
break;
330 if (!response.
IsOK()) {
331 printf(
"Encoder ID %d failed config with error %s\n",
GetEncoder().GetDeviceID(), response.
GetName());
338 encoderConfigs.PWM2.AbsoluteSensorOffset = constants.
EncoderOffset;
342 response =
GetEncoder().GetConfigurator().Apply(encoderConfigs.PWM2);
343 if (response.
IsOK())
break;
345 if (!response.
IsOK()) {
346 printf(
"Encoder ID %d failed config with error %s\n",
GetEncoder().GetDeviceID(), response.
GetName());
365 return _module->Apply(moduleRequest);
377 std::derived_from<controls::ControlRequest> DriveReq,
378 std::derived_from<controls::ControlRequest> SteerReq
380 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
382 return _module->Apply(std::forward<DriveReq>(driveRequest), std::forward<SteerReq>(steerRequest));
396 return _module->GetPosition(refresh);
408 return _module->GetCachedPosition();
421 return _module->GetCurrentVelocity();
433 return _module->GetTargetVelocity();
441 return _module->ResetPosition();
451 return _module->GetDriveClosedLoopOutputType();
461 return _module->GetSteerClosedLoopOutputType();
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
virtual ~SwerveModule()=default
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