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

Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain. More...

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

Inheritance diagram for ctre::phoenix6::swerve::requests::ApplyRobotSpeeds:
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.
 
ApplyRobotSpeedsWithSpeeds (ChassisSpeeds newSpeeds) &
 Modifies the Speeds parameter and returns itself.
 
ApplyRobotSpeeds && WithSpeeds (ChassisSpeeds newSpeeds) &&
 Modifies the Speeds parameter and returns itself.
 
ApplyRobotSpeedsWithWheelForceFeedforwardsX (std::vector< units::newton_t > newWheelForceFeedforwardsX) &
 Modifies the WheelForceFeedforwardsX parameter and returns itself.
 
ApplyRobotSpeeds && WithWheelForceFeedforwardsX (std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
 Modifies the WheelForceFeedforwardsX parameter and returns itself.
 
ApplyRobotSpeedsWithWheelForceFeedforwardsY (std::vector< units::newton_t > newWheelForceFeedforwardsY) &
 Modifies the WheelForceFeedforwardsY parameter and returns itself.
 
ApplyRobotSpeeds && WithWheelForceFeedforwardsY (std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
 Modifies the WheelForceFeedforwardsY parameter and returns itself.
 
ApplyRobotSpeedsWithCenterOfRotation (Translation2d newCenterOfRotation) &
 Modifies the CenterOfRotation parameter and returns itself.
 
ApplyRobotSpeeds && WithCenterOfRotation (Translation2d newCenterOfRotation) &&
 Modifies the CenterOfRotation parameter and returns itself.
 
ApplyRobotSpeedsWithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
 Modifies the DriveRequestType parameter and returns itself.
 
ApplyRobotSpeeds && WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
 Modifies the DriveRequestType parameter and returns itself.
 
ApplyRobotSpeedsWithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
 Modifies the DriveRequestType parameter and returns itself.
 
ApplyRobotSpeeds && WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
 Modifies the DriveRequestType parameter and returns itself.
 
ApplyRobotSpeedsWithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds) &
 Modifies the DesaturateWheelSpeeds parameter and returns itself.
 
ApplyRobotSpeeds && WithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds) &&
 Modifies the DesaturateWheelSpeeds parameter and returns itself.
 
- Public Member Functions inherited from ctre::phoenix6::swerve::requests::SwerveRequest
virtual ~SwerveRequest ()=default
 

Public Attributes

ChassisSpeeds Speeds {}
 The robot-centric chassis speeds to apply to the drivetrain.
 
std::vector< units::newton_t > WheelForceFeedforwardsX
 Robot-centric wheel force feedforwards to apply in the X direction.
 
std::vector< units::newton_t > WheelForceFeedforwardsY
 Robot-centric wheel force feedforwards to apply in the Y direction.
 
Translation2d CenterOfRotation {}
 The center of rotation to rotate around.
 
impl::SwerveModuleImpl::DriveRequestType DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage
 The type of control request to use for the drive motor.
 
impl::SwerveModuleImpl::SteerRequestType SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::Position
 The type of control request to use for the steer motor.
 
bool DesaturateWheelSpeeds = true
 Whether to desaturate wheel speeds before applying.
 

Additional Inherited Members

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

Detailed Description

Accepts a generic robot-centric ChassisSpeeds to apply to the drivetrain.

Member Function Documentation

◆ Apply()

ctre::phoenix::StatusCode ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::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() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithCenterOfRotation ( Translation2d newCenterOfRotation) &
inline

Modifies the CenterOfRotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters
newCenterOfRotationParameter to modify
Returns
this object

◆ WithCenterOfRotation() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithCenterOfRotation ( Translation2d newCenterOfRotation) &&
inline

Modifies the CenterOfRotation parameter and returns itself.

The center of rotation the robot should rotate around. This is (0,0) by default, which will rotate around the center of the robot.

Parameters
newCenterOfRotationParameter to modify
Returns
this object

◆ WithDesaturateWheelSpeeds() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithDesaturateWheelSpeeds ( bool newDesaturateWheelSpeeds) &
inline

Modifies the DesaturateWheelSpeeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.

Parameters
newDesaturateWheelSpeedsParameter to modify
Returns
this object

◆ WithDesaturateWheelSpeeds() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithDesaturateWheelSpeeds ( bool newDesaturateWheelSpeeds) &&
inline

Modifies the DesaturateWheelSpeeds parameter and returns itself.

Whether to desaturate wheel speeds before applying. For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.

Parameters
newDesaturateWheelSpeedsParameter to modify
Returns
this object

◆ WithDriveRequestType() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithDriveRequestType ( impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
inline

Modifies the DriveRequestType parameter and returns itself.

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

Parameters
newDriveRequestTypeParameter to modify
Returns
this object

◆ WithDriveRequestType() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithDriveRequestType ( impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
inline

Modifies the DriveRequestType parameter and returns itself.

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

Parameters
newDriveRequestTypeParameter to modify
Returns
this object

◆ WithSpeeds() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithSpeeds ( ChassisSpeeds newSpeeds) &
inline

Modifies the Speeds parameter and returns itself.

The robot-centric chassis speeds to apply to the drivetrain.

Parameters
newSpeedsParameter to modify
Returns
this object

◆ WithSpeeds() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithSpeeds ( ChassisSpeeds newSpeeds) &&
inline

Modifies the Speeds parameter and returns itself.

The robot-centric chassis speeds to apply to the drivetrain.

Parameters
newSpeedsParameter to modify
Returns
this object

◆ WithSteerRequestType() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithSteerRequestType ( impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
inline

Modifies the DriveRequestType parameter and returns itself.

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

Parameters
newSteerRequestTypeParameter to modify
Returns
this object

◆ WithSteerRequestType() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithSteerRequestType ( impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
inline

Modifies the DriveRequestType parameter and returns itself.

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

Parameters
newSteerRequestTypeParameter to modify
Returns
this object

◆ WithWheelForceFeedforwardsX() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithWheelForceFeedforwardsX ( std::vector< units::newton_t > newWheelForceFeedforwardsX) &
inline

Modifies the WheelForceFeedforwardsX parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters
newWheelForceFeedforwardsXParameter to modify
Returns
this object

◆ WithWheelForceFeedforwardsX() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithWheelForceFeedforwardsX ( std::vector< units::newton_t > newWheelForceFeedforwardsX) &&
inline

Modifies the WheelForceFeedforwardsX parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters
newWheelForceFeedforwardsXParameter to modify
Returns
this object

◆ WithWheelForceFeedforwardsY() [1/2]

ApplyRobotSpeeds & ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithWheelForceFeedforwardsY ( std::vector< units::newton_t > newWheelForceFeedforwardsY) &
inline

Modifies the WheelForceFeedforwardsY parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters
newWheelForceFeedforwardsYParameter to modify
Returns
this object

◆ WithWheelForceFeedforwardsY() [2/2]

ApplyRobotSpeeds && ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WithWheelForceFeedforwardsY ( std::vector< units::newton_t > newWheelForceFeedforwardsY) &&
inline

Modifies the WheelForceFeedforwardsY parameter and returns itself.

Robot-centric wheel force feedforwards to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

Parameters
newWheelForceFeedforwardsYParameter to modify
Returns
this object

Member Data Documentation

◆ CenterOfRotation

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

The center of rotation to rotate around.

◆ DesaturateWheelSpeeds

bool ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::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::ApplyRobotSpeeds::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage

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

◆ Speeds

ChassisSpeeds ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::Speeds {}

The robot-centric chassis speeds to apply to the drivetrain.

◆ SteerRequestType

impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::Position

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

◆ WheelForceFeedforwardsX

std::vector<units::newton_t> ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WheelForceFeedforwardsX

Robot-centric wheel force feedforwards to apply in the X direction.

X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.

◆ WheelForceFeedforwardsY

std::vector<units::newton_t> ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WheelForceFeedforwardsY

Robot-centric wheel force feedforwards to apply in the Y direction.

Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

These forces should include friction applied to the ground.

The order of the forces should match the order of the modules returned from SwerveDrivetrain.


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