CTRE Phoenix 6 C++ 24.50.0-alpha-2
ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl Class Reference

Swerve Drive class utilizing CTR Electronics Phoenix 6 API. More...

#include <ctre/phoenix6/swerve/impl/SwerveDrivetrainImpl.hpp>

Classes

struct  ControlParameters
 Contains everything the control requests need to calculate the module state. More...
 
class  OdometryThread
 Performs swerve module updates in a separate thread to minimize latency. More...
 
struct  SwerveDriveState
 Plain-Old-Data class holding the state of the swerve drivetrain. More...
 

Public Types

using SwerveRequestFunc = std::function< ctre::phoenix::StatusCode(ControlParameters const &, std::vector< std::unique_ptr< SwerveModuleImpl > > const &)>
 

Public Member Functions

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, span< SwerveModuleConstants const > modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, span< SwerveModuleConstants const > modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, ModuleConstants const &... modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
 SwerveDrivetrainImpl (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, std::array< double, 3 > const &odometryStandardDeviation, std::array< double, 3 > const &visionStandardDeviation, span< SwerveModuleConstants const > modules)
 Constructs a CTRE SwerveDrivetrainImpl using the specified constants. More...
 
OdometryThreadGetDaqThread ()
 Gets a reference to the data acquisition thread. More...
 
void SetControl (SwerveRequestFunc &&request)
 Applies the specified control function to this swerve drivetrain. More...
 
ctre::phoenix::StatusCode ConfigNeutralMode (signals::NeutralModeValue neutralMode)
 Configures the neutral mode to use for all modules' drive motors. More...
 
void TareEverything ()
 Zero's this swerve drive's odometry entirely. More...
 
void SeedFieldRelative ()
 Takes the current orientation of the robot and makes it X forward for field-relative maneuvers. More...
 
void SeedFieldRelative (Pose2d location)
 Takes the specified location and makes it the current pose for field-relative maneuvers. More...
 
void SetOperatorPerspectiveForward (Rotation2d fieldDirection)
 Takes the requests::SwerveRequest::ForwardReference::RedAlliance perpective direction and treats it as the forward direction for requests::SwerveRequest::ForwardReference::OperatorPerspective. More...
 
bool IsOdometryValid () const
 Check if the odometry is currently valid. More...
 
SwerveModuleImplGetModule (size_t index)
 Get a reference to the module at the specified index. More...
 
SwerveModuleImpl const & GetModule (size_t index) const
 Get a reference to the module at the specified index. More...
 
std::vector< std::unique_ptr< SwerveModuleImpl > > const & GetModules () const
 Get a reference to the full array of modules. More...
 
std::vector< Translation2d > const & GetModuleLocations () const
 Gets the locations of the swerve modules. More...
 
SwerveDriveState GetState () const
 Gets the current state of the swerve drivetrain. More...
 
void AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp)
 Adds a vision measurement to the Kalman Filter. More...
 
void AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
 Adds a vision measurement to the Kalman Filter. More...
 
void SetVisionMeasurementStdDevs (std::array< double, 3 > visionMeasurementStdDevs)
 Sets the pose estimator's trust of global measurements. More...
 
void RegisterTelemetry (std::function< void(SwerveDriveState const &)> telemetryFunction)
 Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry thread. More...
 
hardware::core::CorePigeon2GetPigeon2 ()
 Gets this drivetrain's Pigeon 2 reference. More...
 

Protected Attributes

CANBus _canbus
 
bool _isOnCANFD
 
units::hertz_t _updateFrequency
 
hardware::core::CorePigeon2 _pigeon2
 
StatusSignal< units::degree_t > _pigeonYaw
 
StatusSignal< units::degrees_per_second_t > _pigeonAngularVelocity
 
std::vector< std::unique_ptr< SwerveModuleImpl > > _modules
 
std::vector< Translation2d > _moduleLocations
 
std::vector< SwerveModulePosition_modulePositions
 
std::vector< SwerveModuleState_moduleStates
 
SwerveDriveKinematics _kinematics
 
SwerveDrivePoseEstimator _odometry
 
Rotation2d _fieldRelativeOffset {}
 
Rotation2d _operatorForwardDirection {}
 
SwerveRequestFunc _requestToApply = [](auto&, auto&) { return ctre::phoenix::StatusCode::OK; }
 
ControlParameters _requestParameters {}
 
std::recursive_mutex _stateLock
 
SwerveDriveState _cachedState {}
 
std::function< void(SwerveDriveState const &)> _telemetryFunction {}
 
std::unique_ptr< OdometryThread_odometryThread
 

Friends

class OdometryThread
 

Detailed Description

Swerve Drive class utilizing CTR Electronics Phoenix 6 API.

This class handles the kinematics and odometry (but not configuration) of a swerve drive utilizing CTR Electronics devices. Users should create a high-level SwerveDrivetrain instead of using this directly.

Member Typedef Documentation

◆ SwerveRequestFunc

Constructor & Destructor Documentation

◆ SwerveDrivetrainImpl() [1/6]

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
ModuleConstants const &...  modules 
)
inline

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
modulesConstants for each specific module

◆ SwerveDrivetrainImpl() [2/6]

ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
span< SwerveModuleConstants const >  modules 
)
inline

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
modulesConstants for each specific module

◆ SwerveDrivetrainImpl() [3/6]

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
units::hertz_t  odometryUpdateFrequency,
ModuleConstants const &...  modules 
)
inline

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
odometryUpdateFrequencyThe frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0.
modulesConstants for each specific module

◆ SwerveDrivetrainImpl() [4/6]

ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
units::hertz_t  odometryUpdateFrequency,
span< SwerveModuleConstants const >  modules 
)
inline

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
odometryUpdateFrequencyThe frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0.
modulesConstants for each specific module

◆ SwerveDrivetrainImpl() [5/6]

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
units::hertz_t  odometryUpdateFrequency,
std::array< double, 3 > const &  odometryStandardDeviation,
std::array< double, 3 > const &  visionStandardDeviation,
ModuleConstants const &...  modules 
)
inline

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
odometryUpdateFrequencyThe frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0.
odometryStandardDeviationThe standard deviation for odometry calculation
visionStandardDeviationThe standard deviation for vision calculation
modulesConstants for each specific module

◆ SwerveDrivetrainImpl() [6/6]

ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SwerveDrivetrainImpl ( SwerveDrivetrainConstants const &  drivetrainConstants,
units::hertz_t  odometryUpdateFrequency,
std::array< double, 3 > const &  odometryStandardDeviation,
std::array< double, 3 > const &  visionStandardDeviation,
span< SwerveModuleConstants const >  modules 
)

Constructs a CTRE SwerveDrivetrainImpl using the specified constants.

This constructs the underlying hardware devices, so user should not construct the devices themselves. If they need the devices, they can access them through getters in the classes.

Parameters
drivetrainConstantsDrivetrain-wide constants for the swerve drive
odometryUpdateFrequencyThe frequency to run the odometry loop. If unspecified or set to 0 Hz, this is 250 Hz on CAN FD, and 100 Hz on CAN 2.0.
odometryStandardDeviationThe standard deviation for odometry calculation
visionStandardDeviationThe standard deviation for vision calculation
modulesConstants for each specific module

Member Function Documentation

◆ AddVisionMeasurement() [1/2]

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::AddVisionMeasurement ( Pose2d  visionRobotPose,
units::second_t  timestamp 
)
inline

Adds a vision measurement to the Kalman Filter.

This will correct the odometry pose estimate while still accounting for measurement noise.

This method can be called as infrequently as you want, as long as you are calling impl::SwerveDrivePoseEstimator::Update every loop.

To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.

Parameters
visionRobotPoseThe pose of the robot as measured by the vision camera.
timestampThe timestamp of the vision measurement in seconds. Note that if you don't use your own time source by calling impl::SwerveDrivePoseEstimator::UpdateWithTime, then you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as GetCurrentTimeSeconds). This means that you should use GetCurrentTimeSeconds as your time source in this case.

◆ AddVisionMeasurement() [2/2]

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::AddVisionMeasurement ( Pose2d  visionRobotPose,
units::second_t  timestamp,
std::array< double, 3 >  visionMeasurementStdDevs 
)
inline

Adds a vision measurement to the Kalman Filter.

This will correct the odometry pose estimate while still accounting for measurement noise.

This method can be called as infrequently as you want, as long as you are calling impl::SwerveDrivePoseEstimator::Update every loop.

To promote stability of the pose estimate and make it robust to bad vision data, we recommend only adding vision measurements that are already within one meter or so of the current pose estimate.

Note that the vision measurement standard deviations passed into this method will continue to apply to future measurements until a subsequent call to SetVisionMeasurementStdDevs or this method.

Parameters
visionRobotPoseThe pose of the robot as measured by the vision camera.
timestampThe timestamp of the vision measurement in seconds. Note that if you don't use your own time source by calling impl::SwerveDrivePoseEstimator::UpdateWithTime, then you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as GetCurrentTimeSeconds). This means that you should use GetCurrentTimeSeconds as your time source in this case.
visionMeasurementStdDevsStandard deviations of the vision pose measurement (x position in meters, y position in meters, and heading in radians). Increase these numbers to trust the vision pose measurement less.

◆ ConfigNeutralMode()

ctre::phoenix::StatusCode ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::ConfigNeutralMode ( signals::NeutralModeValue  neutralMode)
inline

Configures the neutral mode to use for all modules' drive motors.

Parameters
neutralModeThe drive motor neutral mode
Returns
Status code of the first failed config call, or OK if all succeeded

◆ GetDaqThread()

OdometryThread & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetDaqThread ( )
inline

Gets a reference to the data acquisition thread.

Returns
DAQ thread

◆ GetModule() [1/2]

SwerveModuleImpl & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetModule ( size_t  index)
inline

Get a reference to the module at the specified index.

The index corresponds to the module described in the constructor.

Parameters
indexWhich module to get
Returns
Reference to SwerveModuleImpl

◆ GetModule() [2/2]

SwerveModuleImpl const & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetModule ( size_t  index) const
inline

Get a reference to the module at the specified index.

The index corresponds to the module described in the constructor.

Parameters
indexWhich module to get
Returns
Reference to SwerveModuleImpl

◆ GetModuleLocations()

std::vector< Translation2d > const & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetModuleLocations ( ) const
inline

Gets the locations of the swerve modules.

Returns
Reference to the array of swerve module locations

◆ GetModules()

std::vector< std::unique_ptr< SwerveModuleImpl > > const & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetModules ( ) const
inline

Get a reference to the full array of modules.

The indexes correspond to the module described in the constructor.

Returns
Reference to the SwerveModuleImpl array

◆ GetPigeon2()

hardware::core::CorePigeon2 & ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetPigeon2 ( )
inline

Gets this drivetrain's Pigeon 2 reference.

This should be used only to access signals and change configurations that the swerve drivetrain does not configure itself.

Returns
This drivetrain's Pigeon 2 reference

◆ GetState()

SwerveDriveState ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::GetState ( ) const
inline

Gets the current state of the swerve drivetrain.

Returns
Current state of the drivetrain

◆ IsOdometryValid()

bool ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::IsOdometryValid ( ) const
inline

Check if the odometry is currently valid.

Returns
True if odometry is valid

◆ RegisterTelemetry()

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::RegisterTelemetry ( std::function< void(SwerveDriveState const &)>  telemetryFunction)
inline

Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry thread.

It is imperative that this function is cheap, as it will be executed synchronously with the odometry call; if this takes a long time, it may negatively impact the odometry of this stack.

This can also be used for logging data if the function performs logging instead of telemetry.

Parameters
telemetryFunctionFunction to call for telemetry or logging

◆ SeedFieldRelative() [1/2]

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SeedFieldRelative ( )
inline

Takes the current orientation of the robot and makes it X forward for field-relative maneuvers.

◆ SeedFieldRelative() [2/2]

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SeedFieldRelative ( Pose2d  location)
inline

Takes the specified location and makes it the current pose for field-relative maneuvers.

Parameters
locationPose to make the current pose

◆ SetControl()

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SetControl ( SwerveRequestFunc &&  request)
inline

Applies the specified control function to this swerve drivetrain.

Parameters
requestRequest function to apply

◆ SetOperatorPerspectiveForward()

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SetOperatorPerspectiveForward ( Rotation2d  fieldDirection)
inline

Takes the requests::SwerveRequest::ForwardReference::RedAlliance perpective direction and treats it as the forward direction for requests::SwerveRequest::ForwardReference::OperatorPerspective.

If the operator is in the Blue Alliance Station, this should be 0 degrees. If the operator is in the Red Alliance Station, this should be 180 degrees.

Parameters
fieldDirectionHeading indicating which direction is forward from the requests::SwerveRequest::ForwardReference::RedAlliance perspective

◆ SetVisionMeasurementStdDevs()

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::SetVisionMeasurementStdDevs ( std::array< double, 3 >  visionMeasurementStdDevs)
inline

Sets the pose estimator's trust of global measurements.

This might be used to change trust in vision measurements after the autonomous period, or to change trust as distance to a vision target increases.

Parameters
visionMeasurementStdDevsStandard deviations of the vision measurements. Increase these numbers to trust global measurements from vision less. This matrix is in the form [x, y, theta]ᵀ, with units in meters and radians.

◆ TareEverything()

void ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::TareEverything ( )
inline

Zero's this swerve drive's odometry entirely.

This will zero the entire odometry, and place the robot at 0,0

Friends And Related Function Documentation

◆ OdometryThread

friend class OdometryThread
friend

Member Data Documentation

◆ _cachedState

SwerveDriveState ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_cachedState {}
protected

◆ _canbus

CANBus ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_canbus
protected

◆ _fieldRelativeOffset

Rotation2d ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_fieldRelativeOffset {}
protected

◆ _isOnCANFD

bool ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_isOnCANFD
protected

◆ _kinematics

SwerveDriveKinematics ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_kinematics
protected

◆ _moduleLocations

std::vector<Translation2d> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_moduleLocations
protected

◆ _modulePositions

std::vector<SwerveModulePosition> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_modulePositions
protected

◆ _modules

std::vector<std::unique_ptr<SwerveModuleImpl> > ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_modules
protected

◆ _moduleStates

std::vector<SwerveModuleState> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_moduleStates
protected

◆ _odometry

SwerveDrivePoseEstimator ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_odometry
protected

◆ _odometryThread

std::unique_ptr<OdometryThread> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_odometryThread
protected

◆ _operatorForwardDirection

Rotation2d ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_operatorForwardDirection {}
protected

◆ _pigeon2

hardware::core::CorePigeon2 ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_pigeon2
protected

◆ _pigeonAngularVelocity

StatusSignal<units::degrees_per_second_t> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_pigeonAngularVelocity
protected

◆ _pigeonYaw

StatusSignal<units::degree_t> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_pigeonYaw
protected

◆ _requestParameters

ControlParameters ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_requestParameters {}
protected

◆ _requestToApply

SwerveRequestFunc ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_requestToApply = [](auto&, auto&) { return ctre::phoenix::StatusCode::OK; }
protected

◆ _stateLock

std::recursive_mutex ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_stateLock
mutableprotected

◆ _telemetryFunction

std::function<void(SwerveDriveState const &)> ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_telemetryFunction {}
protected

◆ _updateFrequency

units::hertz_t ctre::phoenix6::swerve::impl::SwerveDrivetrainImpl::_updateFrequency
protected

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