12#include "units/force.h"
13#include "units/torque.h"
129 this->
State = std::move(newState);
147 this->WheelForceFeedforwardX = newWheelForceFeedforwardX;
164 this->WheelForceFeedforwardY = newWheelForceFeedforwardY;
178 this->DriveRequest = newDriveRequest;
191 this->SteerRequest = newSteerRequest;
206 this->UpdatePeriod = newUpdatePeriod;
231 this->EnableFOC = newEnableFOC;
237 std::unique_ptr<hardware::traits::CommonTalon> _driveMotor;
238 std::unique_ptr<hardware::traits::CommonTalon> _steerMotor;
250 struct ModuleSupplem;
251 mutable std::unique_ptr<ModuleSupplem> _moduleSupplem;
256 using turns_per_meter = units::compound_unit<units::turns, units::inverse<units::meters>>;
257 using turns_per_meter_t = units::unit_t<turns_per_meter>;
259 turns_per_meter_t kDriveRotationsPerMeter;
260 units::meter_t kDriveNmPerWheelN;
261 units::scalar_t kCouplingRatioDriveRotorToEncoder;
262 units::meters_per_second_t kSpeedAt12Volts;
266 SwerveModulePosition _currentPosition;
267 SwerveModuleState _targetState;
276 template <
typename DriveMotorConfigsT,
typename SteerMotorConfigsT,
typename EncoderConfigsT>
299 template <
typename DriveReq,
typename SteerReq>
300 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
302 if (_driveMotorFOC) {
303 _driveMotorFOC->
SetControl(driveRequest.WithUpdateFreqHz(0_Hz));
305 _driveMotor->SetControl(driveRequest.WithUpdateFreqHz(0_Hz));
308 if (_steerMotorFOC) {
309 _steerMotorFOC->
SetControl(steerRequest.WithUpdateFreqHz(0_Hz));
311 _steerMotor->SetControl(steerRequest.WithUpdateFreqHz(0_Hz));
354 return SwerveModuleState{_driveVelocity.
GetValue() / kDriveRotationsPerMeter, {_steerPosition.
GetValue()}};
372 _driveMotor->SetPosition(0_tr);
382 return kDriveClosedLoopOutput;
392 return kSteerClosedLoopOutput;
400 struct MotorTorqueFeedforwards {
401 units::newton_meter_t torque;
402 units::ampere_t torqueCurrent;
403 units::volt_t voltage;
406 units::turns_per_second_t ApplyVelocityCorrections(units::turns_per_second_t velocity, units::turn_t targetAngle)
const;
407 MotorTorqueFeedforwards CalculateMotorTorqueFeedforwards(
408 units::newton_t wheelForceFeedforwardX,
409 units::newton_t wheelForceFeedforwardY
414 std::array<BaseStatusSignal *, 4> GetSignals()
416 return std::array<BaseStatusSignal *, 4>{&_drivePosition, &_driveVelocity, &_steerPosition, &_steerVelocity};
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:656
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:758
Contains everything common between Talon motor controllers that support FOC (requires Phoenix Pro).
Definition CommonTalonWithFOC.hpp:27
virtual ctre::phoenix::StatusCode SetControl(const controls::TorqueCurrentFOC &request)=0
Request a specified motor current (field oriented control).
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2303
Swerve Drive class utilizing CTR Electronics Phoenix 6 API.
Definition SwerveDrivetrainImpl.hpp:30
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
Definition SwerveModuleImpl.hpp:60
SwerveModuleState GetCurrentState() const
Get the current state of the module.
Definition SwerveModuleImpl.hpp:352
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:390
SwerveModuleState GetTargetState() const
Get the target state of the module.
Definition SwerveModuleImpl.hpp:364
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:300
ClosedLoopOutputType GetDriveClosedLoopOutputType() const
Gets the closed-loop output type to use for the drive motor.
Definition SwerveModuleImpl.hpp:380
SwerveModulePosition GetPosition(bool refresh)
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compen...
ctre::phoenix::StatusCode ConfigNeutralMode(signals::NeutralModeValue neutralMode, units::second_t timeoutSeconds=0.100_s)
Configures the neutral mode to use for the module's drive motor.
void ResetPosition()
Resets this module's drive motor position to 0 rotations.
Definition SwerveModuleImpl.hpp:369
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModuleImpl.hpp:342
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:24
@ 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:40
@ 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:25
Definition MotionMagicExpoTorqueCurrentFOC.hpp:18
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:154
Contains everything the swerve module needs to apply a request.
Definition SwerveModuleImpl.hpp:65
ModuleRequest & WithSteerRequest(SteerRequestType newSteerRequest)
Modifies the SteerRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:189
DriveRequestType DriveRequest
The type of control request to use for the drive motor.
Definition SwerveModuleImpl.hpp:91
units::newton_t WheelForceFeedforwardY
Robot-centric wheel force feedforward to apply in the Y direction.
Definition SwerveModuleImpl.hpp:86
units::second_t UpdatePeriod
The update period of the module request.
Definition SwerveModuleImpl.hpp:101
ModuleRequest & WithEnableFOC(bool newEnableFOC)
Modifies the EnableFOC parameter and returns itself.
Definition SwerveModuleImpl.hpp:229
ModuleRequest & WithWheelForceFeedforwardY(units::newton_t newWheelForceFeedforwardY)
Modifies the WheelForceFeedforwardY parameter and returns itself.
Definition SwerveModuleImpl.hpp:162
SteerRequestType SteerRequest
The type of control request to use for the steer motor.
Definition SwerveModuleImpl.hpp:95
ModuleRequest & WithDriveRequest(DriveRequestType newDriveRequest)
Modifies the DriveRequest parameter and returns itself.
Definition SwerveModuleImpl.hpp:176
bool EnableFOC
When using Voltage-based control, set to true (default) to use FOC commutation (requires Phoenix Pro)...
Definition SwerveModuleImpl.hpp:117
ModuleRequest & WithState(SwerveModuleState newState)
Modifies the State parameter and returns itself.
Definition SwerveModuleImpl.hpp:127
ModuleRequest & WithWheelForceFeedforwardX(units::newton_t newWheelForceFeedforwardX)
Modifies the WheelForceFeedforwardX parameter and returns itself.
Definition SwerveModuleImpl.hpp:145
units::newton_t WheelForceFeedforwardX
Robot-centric wheel force feedforward to apply in the X direction.
Definition SwerveModuleImpl.hpp:78
SwerveModuleState State
Unoptimized speed and direction the module should target.
Definition SwerveModuleImpl.hpp:69
ModuleRequest & WithUpdatePeriod(units::second_t newUpdatePeriod)
Modifies the UpdatePeriod parameter and returns itself.
Definition SwerveModuleImpl.hpp:204