CTRE Phoenix 6 C++ 24.50.0-alpha-2
ctre::phoenix6::swerve::requests::ApplyChassisSpeeds Class Reference

Accepts a generic ChassisSpeeds to apply to the drivetrain. More...

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

Inheritance diagram for ctre::phoenix6::swerve::requests::ApplyChassisSpeeds:
ctre::phoenix6::swerve::requests::SwerveRequest

Public Member Functions

ctre::phoenix::StatusCode Apply (SwerveRequest::ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override
 Applies this swerve request to the given modules. More...
 
ApplyChassisSpeedsWithSpeeds (impl::ChassisSpeeds speeds)
 Sets the chassis speeds to apply to the drivetrain. More...
 
ApplyChassisSpeedsWithCenterOfRotation (Translation2d centerOfRotation)
 Sets the center of rotation to rotate around. More...
 
ApplyChassisSpeedsWithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType driveRequestType)
 Sets the type of control request to use for the drive motor. More...
 
ApplyChassisSpeedsWithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType steerRequestType)
 Sets the type of control request to use for the steer motor. More...
 
ApplyChassisSpeedsWithDesaturateWheelSpeeds (bool desaturateWheelSpeeds)
 Sets whether to desaturate wheel speeds before applying. More...
 
- Public Member Functions inherited from ctre::phoenix6::swerve::requests::SwerveRequest
virtual ~SwerveRequest ()=default
 
virtual ctre::phoenix::StatusCode Apply (ControlParameters const &parameters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply)=0
 Applies this swerve request to the given modules. More...
 

Public Attributes

impl::ChassisSpeeds Speeds {}
 The chassis speeds to apply to the drivetrain. More...
 
Translation2d CenterOfRotation {}
 The center of rotation to rotate around. More...
 
impl::SwerveModuleImpl::DriveRequestType DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage
 The type of control request to use for the drive motor. More...
 
impl::SwerveModuleImpl::SteerRequestType SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::MotionMagicExpo
 The type of control request to use for the steer motor. More...
 
bool DesaturateWheelSpeeds = true
 Whether to desaturate wheel speeds before applying. More...
 

Additional Inherited Members

- Public Types inherited from ctre::phoenix6::swerve::requests::SwerveRequest
using ControlParameters = impl::SwerveDrivetrainImpl::ControlParameters
 

Detailed Description

Accepts a generic ChassisSpeeds to apply to the drivetrain.

Member Function Documentation

◆ Apply()

ctre::phoenix::StatusCode ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::Apply ( SwerveRequest::ControlParameters const &  parameters,
std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &  modulesToApply 
)
inlineoverridevirtual

Applies this swerve request to the given modules.

This is typically called by the SwerveDrivetrain.

Parameters
parametersParameters the control request needs to calculate the module state
modulesToApplyModules to which the control request is applied
Returns
Status code of sending the request

Implements ctre::phoenix6::swerve::requests::SwerveRequest.

◆ WithCenterOfRotation()

ApplyChassisSpeeds & ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::WithCenterOfRotation ( Translation2d  centerOfRotation)
inline

Sets the center of rotation to rotate around.

Parameters
centerOfRotationCenter of rotation to rotate around
Returns
this request

◆ WithDesaturateWheelSpeeds()

ApplyChassisSpeeds & ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::WithDesaturateWheelSpeeds ( bool  desaturateWheelSpeeds)
inline

Sets whether to desaturate wheel speeds before applying.

For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.

Parameters
desaturateWheelSpeedsWhether to desaturate wheel speeds
Returns
this request

◆ WithDriveRequestType()

ApplyChassisSpeeds & ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::WithDriveRequestType ( impl::SwerveModuleImpl::DriveRequestType  driveRequestType)
inline

Sets the type of control request to use for the drive motor.

Parameters
driveRequestTypeThe type of control request to use for the drive motor
Returns
this request

◆ WithSpeeds()

ApplyChassisSpeeds & ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::WithSpeeds ( impl::ChassisSpeeds  speeds)
inline

Sets the chassis speeds to apply to the drivetrain.

Parameters
speedsChassis speeds to apply to the drivetrain
Returns
this request

◆ WithSteerRequestType()

ApplyChassisSpeeds & ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::WithSteerRequestType ( impl::SwerveModuleImpl::SteerRequestType  steerRequestType)
inline

Sets the type of control request to use for the steer motor.

Parameters
steerRequestTypeThe type of control request to use for the steer motor
Returns
this request

Member Data Documentation

◆ CenterOfRotation

Translation2d ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::CenterOfRotation {}

The center of rotation to rotate around.

◆ DesaturateWheelSpeeds

bool ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::DesaturateWheelSpeeds = true

Whether to desaturate wheel speeds before applying.

For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.

◆ DriveRequestType

impl::SwerveModuleImpl::DriveRequestType ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage

The type of control request to use for the drive motor.

◆ Speeds

impl::ChassisSpeeds ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::Speeds {}

The chassis speeds to apply to the drivetrain.

◆ SteerRequestType

impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::MotionMagicExpo

The type of control request to use for the steer motor.


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