13#include "units/force.h"
14#include "units/torque.h"
130 this->
State = std::move(newState);
148 this->WheelForceFeedforwardX = newWheelForceFeedforwardX;
165 this->WheelForceFeedforwardY = newWheelForceFeedforwardY;
179 this->DriveRequest = newDriveRequest;
192 this->SteerRequest = newSteerRequest;
207 this->UpdatePeriod = newUpdatePeriod;
232 this->EnableFOC = newEnableFOC;
238 std::unique_ptr<hardware::traits::CommonTalon> _driveMotor;
239 std::unique_ptr<hardware::traits::CommonTalon> _steerMotor;
252 struct ModuleSupplem;
253 mutable std::unique_ptr<ModuleSupplem> _moduleSupplem;
258 using turns_per_meter = units::compound_unit<units::turns, units::inverse<units::meters>>;
259 using turns_per_meter_t = units::unit_t<turns_per_meter>;
261 turns_per_meter_t kDriveRotationsPerMeter;
262 units::meter_t kDriveNmPerWheelN;
263 units::scalar_t kCouplingRatioDriveRotorToEncoder;
264 units::meters_per_second_t kSpeedAt12Volts;
268 SwerveModulePosition _currentPosition;
269 SwerveModuleState _targetState;
279 std::derived_from<configs::ParentConfiguration> DriveMotorConfigsT,
280 std::derived_from<configs::ParentConfiguration> SteerMotorConfigsT,
281 std::derived_from<configs::ParentConfiguration> EncoderConfigsT
306 std::derived_from<controls::ControlRequest> DriveReq,
307 std::derived_from<controls::ControlRequest> SteerReq
309 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
311 if (_driveMotorFOC) {
312 _driveMotorFOC->
SetControl(driveRequest.WithUpdateFreqHz(0_Hz));
314 _driveMotor->SetControl(driveRequest.WithUpdateFreqHz(0_Hz));
317 if (_steerMotorFOC) {
318 _steerMotorFOC->
SetControl(steerRequest.WithUpdateFreqHz(0_Hz));
320 _steerMotor->SetControl(steerRequest.WithUpdateFreqHz(0_Hz));
363 return SwerveModuleState{_driveVelocity.
GetValue() / kDriveRotationsPerMeter, {_steerPosition.
GetValue()}};
381 _driveMotor->SetPosition(0_tr);
391 return kDriveClosedLoopOutput;
401 return kSteerClosedLoopOutput;
409 struct MotorTorqueFeedforwards {
410 units::newton_meter_t torque;
411 units::ampere_t torqueCurrent;
412 units::volt_t voltage;
415 units::turns_per_second_t ApplyVelocityCorrections(units::turns_per_second_t velocity, units::turn_t targetAngle)
const;
416 MotorTorqueFeedforwards CalculateMotorTorqueFeedforwards(
417 units::newton_t wheelForceFeedforwardX,
418 units::newton_t wheelForceFeedforwardY
423 std::array<BaseStatusSignal *, 4> GetSignals()
425 return std::array<BaseStatusSignal *, 4>{&_drivePosition, &_driveVelocity, &_steerPosition, &_steerVelocity};
429 return _encoderPosition;
Class for getting information about an available CAN bus.
Definition CANBus.hpp:19
Represents a status signal with data of type T, and operations available to retrieve information abou...
Definition StatusSignal.hpp:474
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:522
Contains everything common between Talon motor controllers that support FOC (requires Phoenix Pro).
Definition CommonTalonWithFOC.hpp:28
virtual ctre::phoenix::StatusCode SetControl(const controls::TorqueCurrentFOC &request)=0
Request a specified motor current (field oriented control).
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:29
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
SwerveModuleImpl(SwerveModuleConstants< DriveMotorConfigsT, SteerMotorConfigsT, EncoderConfigsT > const &constants, CANBus canbus)
Construct a SwerveModuleImpl with the specified constants.
ClosedLoopOutputType GetSteerClosedLoopOutputType() const
Gets the closed-loop output type to use for the steer motor.
Definition SwerveModuleImpl.hpp:399
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds)
Configures the neutral mode to use for the module's drive motor.
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.
void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
Controls this module using the specified drive and steer control requests.
Definition SwerveModuleImpl.hpp:309
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
@ MotionMagicExpo
Control the drive motor using a Motion Magic® Expo request.
@ Position
Control the drive motor using an unprofiled position request.
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:41
@ Velocity
Control the drive motor using a velocity closed-loop request.
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
ClosedLoopOutputType
Supported closed-loop output types.
Definition SwerveModuleConstants.hpp:22
Definition motor_constants.h:14
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:1603
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:148
Contains everything the swerve module needs to apply a request.
Definition SwerveModuleImpl.hpp:66
ModuleRequest & WithSteerRequest(SteerRequestType newSteerRequest)
Modifies the SteerRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:190
DriveRequestType DriveRequest
The type of control request to use for the drive motor.
Definition SwerveModuleImpl.hpp:92
units::newton_t WheelForceFeedforwardY
Robot-centric wheel force feedforward to apply in the Y direction.
Definition SwerveModuleImpl.hpp:87
units::second_t UpdatePeriod
The update period of the module request.
Definition SwerveModuleImpl.hpp:102
ModuleRequest & WithEnableFOC(bool newEnableFOC)
Modifies the EnableFOC parameter and returns itself.
Definition SwerveModuleImpl.hpp:230
ModuleRequest & WithWheelForceFeedforwardY(units::newton_t newWheelForceFeedforwardY)
Modifies the WheelForceFeedforwardY parameter and returns itself.
Definition SwerveModuleImpl.hpp:163
SteerRequestType SteerRequest
The type of control request to use for the steer motor.
Definition SwerveModuleImpl.hpp:96
ModuleRequest & WithDriveRequest(DriveRequestType newDriveRequest)
Modifies the DriveRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:177
bool EnableFOC
When using Voltage-based control, set to true (default) to use FOC commutation (requires Phoenix Pro)...
Definition SwerveModuleImpl.hpp:118
ModuleRequest & WithState(SwerveModuleState newState)
Modifies the State parameter and returns itself.
Definition SwerveModuleImpl.hpp:128
ModuleRequest & WithWheelForceFeedforwardX(units::newton_t newWheelForceFeedforwardX)
Modifies the WheelForceFeedforwardX parameter and returns itself.
Definition SwerveModuleImpl.hpp:146
units::newton_t WheelForceFeedforwardX
Robot-centric wheel force feedforward to apply in the X direction.
Definition SwerveModuleImpl.hpp:79
SwerveModuleState State
Unoptimized speed and direction the module should target.
Definition SwerveModuleImpl.hpp:70
ModuleRequest & WithUpdatePeriod(units::second_t newUpdatePeriod)
Modifies the UpdatePeriod parameter and returns itself.
Definition SwerveModuleImpl.hpp:205