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

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

#include <ctre/phoenix6/swerve/SwerveDrivetrain.hpp>

Public Types

using OdometryThread = impl::SwerveDrivetrainImpl::OdometryThread
 Performs swerve module updates in a separate thread to minimize latency.
 
using SwerveDriveState = impl::SwerveDrivetrainImpl::SwerveDriveState
 Plain-Old-Data class holding the state of the swerve drivetrain.
 

Public Member Functions

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrain (SwerveDrivetrainConstants const &drivetrainConstants, ModuleConstants const &... modules)
 Constructs a CTRE SwerveDrivetrain using the specified constants.
 
template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrain (SwerveDrivetrainConstants const &drivetrainConstants, units::hertz_t odometryUpdateFrequency, ModuleConstants const &... modules)
 Constructs a CTRE SwerveDrivetrain using the specified constants.
 
template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
 SwerveDrivetrain (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 SwerveDrivetrain using the specified constants.
 
virtual ~SwerveDrivetrain ()=default
 
virtual void UpdateSimState (units::second_t dt, units::volt_t supplyVoltage)
 Updates all the simulation state variables for this drivetrain class.
 
bool IsOnCANFD () const
 Gets whether the drivetrain is on a CAN FD bus.
 
units::hertz_t GetOdometryFrequency () const
 Gets the target odometry update frequency.
 
OdometryThreadGetOdometryThread ()
 Gets a reference to the odometry thread.
 
virtual bool IsOdometryValid () const
 Check if the odometry is currently valid.
 
impl::SwerveDriveKinematics const & GetKinematics () const
 Gets a reference to the kinematics used for the drivetrain.
 
template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>>
void SetControl (Request &request)
 Applies the specified control request to this swerve drivetrain.
 
template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>>
void SetControl (Request &&request)
 Applies the specified control request to this swerve drivetrain.
 
SwerveDriveState GetState () const
 Gets the current state of the swerve drivetrain.
 
virtual void RegisterTelemetry (std::function< void(SwerveDriveState const &)> telemetryFunction)
 Register the specified lambda to be executed whenever the SwerveDriveState is updated in the odometry thread.
 
virtual ctre::phoenix::StatusCode ConfigNeutralMode (signals::NeutralModeValue neutralMode)
 Configures the neutral mode to use for all modules' drive motors.
 
virtual void TareEverything ()
 Zero's this swerve drive's odometry entirely.
 
virtual void SeedFieldCentric ()
 Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspective perspective.
 
virtual void ResetPose (Pose2d const &pose)
 Resets the pose of the robot.
 
virtual void ResetTranslation (Translation2d const &translation)
 Resets the translation of the robot pose without affecting rotation.
 
virtual void ResetRotation (Rotation2d const &rotation)
 Resets the rotation of the robot pose without affecting translation.
 
virtual void SetOperatorPerspectiveForward (Rotation2d fieldDirection)
 Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the forward direction for requests::ForwardPerspectiveValue::OperatorPerspective.
 
Rotation2d GetOperatorForwardDirection () const
 Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as the forward direction for requests::ForwardPerspectiveValue::OperatorPerspective.
 
virtual void AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp)
 Adds a vision measurement to the Kalman Filter.
 
virtual void AddVisionMeasurement (Pose2d visionRobotPose, units::second_t timestamp, std::array< double, 3 > visionMeasurementStdDevs)
 Adds a vision measurement to the Kalman Filter.
 
virtual void SetVisionMeasurementStdDevs (std::array< double, 3 > visionMeasurementStdDevs)
 Sets the pose estimator's trust of global measurements.
 
virtual std::optional< Pose2d > SamplePoseAt (units::second_t timestamp)
 Return the pose at a given timestamp, if the buffer is not empty.
 
SwerveModuleGetModule (size_t index)
 Get a reference to the module at the specified index.
 
SwerveModule const & GetModule (size_t index) const
 Get a reference to the module at the specified index.
 
std::vector< std::unique_ptr< SwerveModule > > const & GetModules () const
 Get a reference to the full array of modules.
 
std::vector< Translation2d > const & GetModuleLocations () const
 Gets the locations of the swerve modules.
 
frc::Rotation3d GetRotation3d () const
 Gets the current orientation of the robot as a frc::Rotation3d from the Pigeon 2 quaternion values.
 
hardware::Pigeon2GetPigeon2 ()
 Gets this drivetrain's Pigeon 2 reference.
 

Protected Attributes

impl::SwerveDrivetrainImpl _drivetrain
 The underlying drivetrain instance.
 

Static Protected Attributes

static constexpr int kNumConfigAttempts = 2
 Number of times to attempt config applies.
 

Detailed Description

Swerve Drive class utilizing CTR Electronics Phoenix 6 API.

This class handles the kinematics, configuration, and odometry of a swerve drive utilizing CTR Electronics devices. We recommend using the Swerve Project Generator in Tuner X to create a template project that demonstrates how to use this class.

This class performs pose estimation internally using a separate odometry thread. Vision measurements can be added using AddVisionMeasurement. Other odometry APIs such as ResetPose are also available. The resulting pose estimate can be retrieved along with module states and other information using GetState. Additionally, the odometry thread synchronously provides all new state updates to a telemetry function registered with RegisterTelemetry.

This class will construct the hardware devices internally, so the user only specifies the constants (IDs, PID gains, gear ratios, etc). Getters for these hardware devices are available.

If using the generator, the order in which modules are constructed is Front Left, Front Right, Back Left, Back Right. This means if you need the Back Left module, call GetModule(2); to get the third (0-indexed) module.

Member Typedef Documentation

◆ OdometryThread

Performs swerve module updates in a separate thread to minimize latency.

◆ SwerveDriveState

Plain-Old-Data class holding the state of the swerve drivetrain.

This encapsulates most data that is relevant for telemetry or decision-making from the Swerve Drive.

Constructor & Destructor Documentation

◆ SwerveDrivetrain() [1/3]

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

Constructs a CTRE SwerveDrivetrain using the specified constants.

This constructs the underlying hardware devices, so users 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

◆ SwerveDrivetrain() [2/3]

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

Constructs a CTRE SwerveDrivetrain using the specified constants.

This constructs the underlying hardware devices, so users 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

◆ SwerveDrivetrain() [3/3]

template<typename... ModuleConstants, typename = std::enable_if_t< std::conjunction_v<std::is_same<ModuleConstants, SwerveModuleConstants>...> >>
ctre::phoenix6::swerve::SwerveDrivetrain::SwerveDrivetrain ( 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 SwerveDrivetrain using the specified constants.

This constructs the underlying hardware devices, so users 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 in the form [x, y, theta]ᵀ, with units in meters and radians
visionStandardDeviationThe standard deviation for vision calculation in the form [x, y, theta]ᵀ, with units in meters and radians
modulesConstants for each specific module

◆ ~SwerveDrivetrain()

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

Member Function Documentation

◆ AddVisionMeasurement() [1/2]

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::AddVisionMeasurement ( Pose2d visionRobotPose,
units::second_t timestamp )
inlinevirtual

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 you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime). This means that you should use utils::GetCurrentTime as your time source in this case. An FPGA timestamp can be converted to the correct timebase using utils::FPGAToCurrentTime.

◆ AddVisionMeasurement() [2/2]

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::AddVisionMeasurement ( Pose2d visionRobotPose,
units::second_t timestamp,
std::array< double, 3 > visionMeasurementStdDevs )
inlinevirtual

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 you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime). This means that you should use utils::GetCurrentTime as your time source in this case. An FPGA timestamp can be converted to the correct timebase using utils::FPGAToCurrentTime.
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()

virtual ctre::phoenix::StatusCode ctre::phoenix6::swerve::SwerveDrivetrain::ConfigNeutralMode ( signals::NeutralModeValue neutralMode)
inlinevirtual

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

◆ GetKinematics()

impl::SwerveDriveKinematics const & ctre::phoenix6::swerve::SwerveDrivetrain::GetKinematics ( ) const
inline

Gets a reference to the kinematics used for the drivetrain.

Returns
Swerve kinematics

◆ GetModule() [1/2]

SwerveModule & ctre::phoenix6::swerve::SwerveDrivetrain::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 SwerveModule

◆ GetModule() [2/2]

SwerveModule const & ctre::phoenix6::swerve::SwerveDrivetrain::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 SwerveModule

◆ GetModuleLocations()

std::vector< Translation2d > const & ctre::phoenix6::swerve::SwerveDrivetrain::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< SwerveModule > > const & ctre::phoenix6::swerve::SwerveDrivetrain::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 SwerveModule array

◆ GetOdometryFrequency()

units::hertz_t ctre::phoenix6::swerve::SwerveDrivetrain::GetOdometryFrequency ( ) const
inline

Gets the target odometry update frequency.

Returns
Target odometry update frequency

◆ GetOdometryThread()

OdometryThread & ctre::phoenix6::swerve::SwerveDrivetrain::GetOdometryThread ( )
inline

Gets a reference to the odometry thread.

Returns
Odometry thread

◆ GetOperatorForwardDirection()

Rotation2d ctre::phoenix6::swerve::SwerveDrivetrain::GetOperatorForwardDirection ( ) const
inline

Returns the requests::ForwardPerspectiveValue::BlueAlliance perpective direction that is treated as the forward direction for requests::ForwardPerspectiveValue::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.

Returns
Heading indicating which direction is forward from the requests::ForwardPerspectiveValue::BlueAlliance perspective

◆ GetPigeon2()

hardware::Pigeon2 & ctre::phoenix6::swerve::SwerveDrivetrain::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

◆ GetRotation3d()

frc::Rotation3d ctre::phoenix6::swerve::SwerveDrivetrain::GetRotation3d ( ) const
inline

Gets the current orientation of the robot as a frc::Rotation3d from the Pigeon 2 quaternion values.

Returns
The robot orientation as a frc::Rotation3d

◆ GetState()

SwerveDriveState ctre::phoenix6::swerve::SwerveDrivetrain::GetState ( ) const
inline

Gets the current state of the swerve drivetrain.

This includes information such as the pose estimate, module states, and chassis speeds.

Returns
Current state of the drivetrain

◆ IsOdometryValid()

virtual bool ctre::phoenix6::swerve::SwerveDrivetrain::IsOdometryValid ( ) const
inlinevirtual

Check if the odometry is currently valid.

Returns
True if odometry is valid

◆ IsOnCANFD()

bool ctre::phoenix6::swerve::SwerveDrivetrain::IsOnCANFD ( ) const
inline

Gets whether the drivetrain is on a CAN FD bus.

Returns
true if on CAN FD

◆ RegisterTelemetry()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::RegisterTelemetry ( std::function< void(SwerveDriveState const &)> telemetryFunction)
inlinevirtual

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. Additionally, the SwerveDriveState object can be cloned and stored for later processing.

Parameters
telemetryFunctionFunction to call for telemetry or logging

◆ ResetPose()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::ResetPose ( Pose2d const & pose)
inlinevirtual

Resets the pose of the robot.

The pose should be from the requests::ForwardPerspectiveValue::BlueAlliance perspective.

Parameters
posePose to make the current pose

◆ ResetRotation()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::ResetRotation ( Rotation2d const & rotation)
inlinevirtual

Resets the rotation of the robot pose without affecting translation.

The rotation should be from the requests::ForwardPerspectiveValue::BlueAlliance perspective.

Parameters
rotationRotation to make the current rotation

◆ ResetTranslation()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::ResetTranslation ( Translation2d const & translation)
inlinevirtual

Resets the translation of the robot pose without affecting rotation.

The translation should be from the requests::ForwardPerspectiveValue::BlueAlliance perspective.

Parameters
translationTranslation to make the current translation

◆ SamplePoseAt()

virtual std::optional< Pose2d > ctre::phoenix6::swerve::SwerveDrivetrain::SamplePoseAt ( units::second_t timestamp)
inlinevirtual

Return the pose at a given timestamp, if the buffer is not empty.

Parameters
timestampThe pose's timestamp. Note that you must use a timestamp with an epoch since system startup (i.e., the epoch of this timestamp is the same epoch as utils::GetCurrentTime). This means that you should use utils::GetCurrentTime as your time source in this case. An FPGA timestamp can be converted to the correct timebase using utils::FPGAToCurrentTime.
Returns
The pose at the given timestamp (or std::nullopt if the buffer is empty).

◆ SeedFieldCentric()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::SeedFieldCentric ( )
inlinevirtual

Resets the rotation of the robot pose to 0 from the requests::ForwardPerspectiveValue::OperatorPerspective perspective.

This makes the current orientation of the robot X forward for field-centric maneuvers.

This is equivalent to calling ResetRotation with the operator perspective rotation.

◆ SetControl() [1/2]

template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>>
void ctre::phoenix6::swerve::SwerveDrivetrain::SetControl ( Request && request)
inline

Applies the specified control request to this swerve drivetrain.

Parameters
requestRequest to apply

◆ SetControl() [2/2]

template<typename Request , typename = std::enable_if_t<std::is_base_of_v<requests::SwerveRequest, Request>>, typename = std::enable_if_t<!std::is_const_v<Request>>>
void ctre::phoenix6::swerve::SwerveDrivetrain::SetControl ( Request & request)
inline

Applies the specified control request to this swerve drivetrain.

This captures the swerve request by reference, so it must live for at least as long as the drivetrain. This can be done by storing the request as a member variable of your drivetrain subsystem or robot.

Parameters
requestRequest to apply

◆ SetOperatorPerspectiveForward()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::SetOperatorPerspectiveForward ( Rotation2d fieldDirection)
inlinevirtual

Takes the requests::ForwardPerspectiveValue::BlueAlliance perpective direction and treats it as the forward direction for requests::ForwardPerspectiveValue::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.

This does not change the robot pose, which is in the requests::ForwardPerspectiveValue::BlueAlliance perspective. As a result, the robot pose may need to be reset using ResetPose.

Parameters
fieldDirectionHeading indicating which direction is forward from the requests::ForwardPerspectiveValue::BlueAlliance perspective

◆ SetVisionMeasurementStdDevs()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::SetVisionMeasurementStdDevs ( std::array< double, 3 > visionMeasurementStdDevs)
inlinevirtual

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()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::TareEverything ( )
inlinevirtual

Zero's this swerve drive's odometry entirely.

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

◆ UpdateSimState()

virtual void ctre::phoenix6::swerve::SwerveDrivetrain::UpdateSimState ( units::second_t dt,
units::volt_t supplyVoltage )
inlinevirtual

Updates all the simulation state variables for this drivetrain class.

User provides the update variables for the simulation.

Parameters
dttime since last update call
supplyVoltagevoltage as seen at the motor controllers

Member Data Documentation

◆ _drivetrain

impl::SwerveDrivetrainImpl ctre::phoenix6::swerve::SwerveDrivetrain::_drivetrain
protected

The underlying drivetrain instance.

◆ kNumConfigAttempts

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

Number of times to attempt config applies.


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