CTRE Phoenix 6 C++ 25.0.0-beta-4
Loading...
Searching...
No Matches
ctre::phoenix6::swerve::SwerveModule Class Reference

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::TalonFXGetDriveMotor ()
 Gets this module's Drive Motor TalonFX reference.
 
hardware::TalonFXGetSteerMotor ()
 Gets this module's Steer Motor TalonFX reference.
 
hardware::CANcoderGetCANcoder ()
 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.
 

Detailed Description

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.

Member Typedef Documentation

◆ DriveRequestType

All possible control requests for the module drive motor.

◆ ModuleRequest

Contains everything the swerve module needs to apply a request.

◆ SteerRequestType

All possible control requests for the module steer motor.

Constructor & Destructor Documentation

◆ SwerveModule()

ctre::phoenix6::swerve::SwerveModule::SwerveModule ( SwerveModuleConstants const & constants,
std::string_view canbusName,
impl::SwerveModuleImpl & module )

Construct a SwerveModule with the specified constants.

Parameters
constantsConstants used to construct the module
canbusNameThe name of the CAN bus this module is on
moduleThe impl::SwerveModuleImpl to use

◆ ~SwerveModule()

virtual ctre::phoenix6::swerve::SwerveModule::~SwerveModule ( )
virtualdefault

Member Function Documentation

◆ Apply() [1/2]

template<typename DriveReq , typename SteerReq >
void ctre::phoenix6::swerve::SwerveModule::Apply ( DriveReq && driveRequest,
SteerReq && steerRequest )
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.

Parameters
driveRequestThe control request to apply to the drive motor
steerRequestThe control request to apply to the steer motor

◆ Apply() [2/2]

virtual void ctre::phoenix6::swerve::SwerveModule::Apply ( ModuleRequest const & moduleRequest)
inlinevirtual

Applies the desired ModuleRequest to this module.

Parameters
moduleRequestThe request to apply to this module

◆ GetCachedPosition()

SwerveModulePosition ctre::phoenix6::swerve::SwerveModule::GetCachedPosition ( ) const
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.

Returns
Last cached SwerveModulePosition

◆ GetCANcoder()

hardware::CANcoder & ctre::phoenix6::swerve::SwerveModule::GetCANcoder ( )
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.

Returns
This module's CANcoder reference

◆ GetCurrentState()

SwerveModuleState ctre::phoenix6::swerve::SwerveModule::GetCurrentState ( ) const
inline

Get the current state of the module.

This is typically used for telemetry, as the SwerveModulePosition is used for odometry.

Returns
Current state of the module

◆ GetDriveMotor()

hardware::TalonFX & ctre::phoenix6::swerve::SwerveModule::GetDriveMotor ( )
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.

Returns
This module's Drive Motor reference

◆ GetPosition()

SwerveModulePosition ctre::phoenix6::swerve::SwerveModule::GetPosition ( bool refresh)
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.

Parameters
refreshTrue if the signals should be refreshed
Returns
SwerveModulePosition containing this module's state.

◆ GetSteerMotor()

hardware::TalonFX & ctre::phoenix6::swerve::SwerveModule::GetSteerMotor ( )
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.

Returns
This module's Steer Motor reference

◆ GetTargetState()

SwerveModuleState ctre::phoenix6::swerve::SwerveModule::GetTargetState ( ) const
inline

Get the target state of the module.

This is typically used for telemetry.

Returns
Target state of the module

◆ ResetPosition()

virtual void ctre::phoenix6::swerve::SwerveModule::ResetPosition ( )
inlinevirtual

Resets this module's drive motor position to 0 rotations.

Member Data Documentation

◆ _module

impl::SwerveModuleImpl* ctre::phoenix6::swerve::SwerveModule::_module
protected

The underlying swerve module instance.

◆ kNumConfigAttempts

constexpr int ctre::phoenix6::swerve::SwerveModule::kNumConfigAttempts = 2
staticconstexprprotected

Number of times to attempt config applies.


The documentation for this class was generated from the following file: