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;
252 using turns_per_meter = units::compound_unit<units::turns, units::inverse<units::meters>>;
253 using turns_per_meter_t = units::unit_t<turns_per_meter>;
255 turns_per_meter_t kDriveRotationsPerMeter;
256 units::meter_t kDriveNmPerWheelN;
257 units::scalar_t kCouplingRatioDriveRotorToCANcoder;
258 units::meters_per_second_t kSpeedAt12Volts;
262 SwerveModulePosition _currentPosition;
263 SwerveModuleState _targetState;
289 template <
typename DriveReq,
typename SteerReq>
290 void Apply(DriveReq &&driveRequest, SteerReq &&steerRequest)
292 _driveMotor.
SetControl(driveRequest.WithUpdateFreqHz(0_Hz));
293 _steerMotor.
SetControl(steerRequest.WithUpdateFreqHz(0_Hz));
335 return SwerveModuleState{_driveVelocity.
GetValue() / kDriveRotationsPerMeter, {_steerPosition.
GetValue()}};
391 struct MotorTorqueFeedforwards {
392 units::newton_meter_t torque;
393 units::ampere_t torqueCurrent;
394 units::volt_t voltage;
397 units::turns_per_second_t ApplyVelocityCorrections(units::turns_per_second_t velocity, units::turn_t targetAngle)
const;
398 MotorTorqueFeedforwards CalculateMotorTorqueFeedforwards(
399 units::newton_t wheelForceFeedforwardX,
400 units::newton_t wheelForceFeedforwardY
405 std::array<BaseStatusSignal *, 4> GetSignals()
407 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:657
T GetValue() const
Gets the cached value from this status signal.
Definition StatusSignal.hpp:759
Class for CANcoder, a CAN based magnetic encoder that provides absolute and relative position along w...
Definition CoreCANcoder.hpp:631
Class description for the Talon FX integrated motor controller.
Definition CoreTalonFX.hpp:2932
ctre::phoenix::StatusCode SetControl(const controls::DutyCycleOut &request) override
Request a specified motor duty cycle.
ctre::phoenix::StatusCode SetPosition(units::angle::turn_t newValue, units::time::second_t timeoutSeconds) override
Sets the mechanism position of the device in mechanism rotations.
Definition CoreTalonFX.hpp:7628
The state of the motor controller bridge when output is neutral or disabled.
Definition SpnEnums.hpp:2202
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:29
SwerveModuleState GetCurrentState() const
Get the current state of the module.
Definition SwerveModuleImpl.hpp:333
DriveRequestType
All possible control requests for the module drive motor.
Definition SwerveModuleImpl.hpp:50
@ Velocity
Control the drive motor using a velocity closed-loop request.
@ OpenLoopVoltage
Control the drive motor using an open-loop voltage request.
hardware::core::CoreTalonFX & GetSteerMotor()
Gets this module's Steer Motor TalonFX reference.
Definition SwerveModuleImpl.hpp:374
hardware::core::CoreCANcoder & GetCANcoder()
Gets this module's CANcoder reference.
Definition SwerveModuleImpl.hpp:384
SteerRequestType
All possible control requests for the module steer motor.
Definition SwerveModuleImpl.hpp:34
@ MotionMagicExpo
Control the drive motor using a Motion Magic® Expo request.
@ Position
Control the drive motor using an unprofiled position request.
SwerveModuleImpl(SwerveModuleConstants const &constants, CANBus canbus)
Construct a SwerveModuleImpl with the specified constants.
SwerveModuleState GetTargetState() const
Get the target state of the module.
Definition SwerveModuleImpl.hpp:345
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:290
SwerveModulePosition GetPosition(bool refresh)
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compen...
hardware::core::CoreTalonFX & GetDriveMotor()
Gets this module's Drive Motor TalonFX reference.
Definition SwerveModuleImpl.hpp:364
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:350
SwerveModulePosition GetCachedPosition() const
Gets the last cached swerve module position.
Definition SwerveModuleImpl.hpp:323
Status codes reported by APIs, including OK, warnings, and errors.
Definition StatusCodes.h:27
ClosedLoopOutputType
Supported closed-loop output types.
Definition SwerveModuleConstants.hpp:23
Definition StatusCodes.h:18
All constants for a swerve module.
Definition SwerveModuleConstants.hpp:53
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