CTRE Phoenix 6 C++ 25.0.0-beta-4
|
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices. More...
#include <ctre/phoenix6/swerve/SwerveModule.hpp>
Public Types | |
using | SteerRequestType = impl::SwerveModuleImpl::SteerRequestType |
All possible control requests for the module steer motor. | |
using | DriveRequestType = impl::SwerveModuleImpl::DriveRequestType |
All possible control requests for the module drive motor. | |
using | ModuleRequest = impl::SwerveModuleImpl::ModuleRequest |
Contains everything the swerve module needs to apply a request. | |
Public Member Functions | |
SwerveModule (SwerveModuleConstants const &constants, std::string_view canbusName, impl::SwerveModuleImpl &module) | |
Construct a SwerveModule with the specified constants. | |
virtual | ~SwerveModule ()=default |
virtual void | Apply (ModuleRequest const &moduleRequest) |
Applies the desired ModuleRequest to this module. | |
template<typename DriveReq , typename SteerReq > | |
void | Apply (DriveReq &&driveRequest, SteerReq &&steerRequest) |
Controls this module using the specified drive and steer control requests. | |
SwerveModulePosition | GetPosition (bool refresh) |
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compensated values. | |
SwerveModulePosition | GetCachedPosition () const |
Gets the last cached swerve module position. | |
SwerveModuleState | GetCurrentState () const |
Get the current state of the module. | |
SwerveModuleState | GetTargetState () const |
Get the target state of the module. | |
virtual void | ResetPosition () |
Resets this module's drive motor position to 0 rotations. | |
hardware::TalonFX & | GetDriveMotor () |
Gets this module's Drive Motor TalonFX reference. | |
hardware::TalonFX & | GetSteerMotor () |
Gets this module's Steer Motor TalonFX reference. | |
hardware::CANcoder & | GetCANcoder () |
Gets this module's CANcoder reference. | |
Protected Attributes | |
impl::SwerveModuleImpl * | _module |
The underlying swerve module instance. | |
Static Protected Attributes | |
static constexpr int | kNumConfigAttempts = 2 |
Number of times to attempt config applies. | |
Swerve Module class that encapsulates a swerve module powered by CTR Electronics devices.
This class handles the hardware devices and configures them for swerve module operation using the Phoenix 6 API.
This class constructs hardware devices internally, so the user only specifies the constants (IDs, PID gains, gear ratios, etc). Getters for these hardware devices are available.
using ctre::phoenix6::swerve::SwerveModule::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType |
All possible control requests for the module drive motor.
Contains everything the swerve module needs to apply a request.
using ctre::phoenix6::swerve::SwerveModule::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType |
All possible control requests for the module steer motor.
ctre::phoenix6::swerve::SwerveModule::SwerveModule | ( | SwerveModuleConstants const & | constants, |
std::string_view | canbusName, | ||
impl::SwerveModuleImpl & | module ) |
Construct a SwerveModule with the specified constants.
constants | Constants used to construct the module |
canbusName | The name of the CAN bus this module is on |
module | The impl::SwerveModuleImpl to use |
|
virtualdefault |
|
inline |
Controls this module using the specified drive and steer control requests.
This is intended only to be used for characterization of the robot; do not use this for normal use.
driveRequest | The control request to apply to the drive motor |
steerRequest | The control request to apply to the steer motor |
|
inlinevirtual |
Applies the desired ModuleRequest to this module.
moduleRequest | The request to apply to this module |
|
inline |
Gets the last cached swerve module position.
This differs from GetPosition in that it will not perform any latency compensation or refresh the signals.
|
inline |
Gets this module's CANcoder reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
|
inline |
Get the current state of the module.
This is typically used for telemetry, as the SwerveModulePosition is used for odometry.
|
inline |
Gets this module's Drive Motor TalonFX reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
|
inline |
Gets the state of this module and passes it back as a SwerveModulePosition object with latency compensated values.
This function is blocking when it performs a refresh.
refresh | True if the signals should be refreshed |
|
inline |
Gets this module's Steer Motor TalonFX reference.
This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.
|
inline |
Get the target state of the module.
This is typically used for telemetry.
|
inlinevirtual |
Resets this module's drive motor position to 0 rotations.
|
protected |
The underlying swerve module instance.
|
staticconstexprprotected |
Number of times to attempt config applies.