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

Drives the swerve drivetrain in a field-centric manner. More...

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

Inheritance diagram for ctre::phoenix6::swerve::requests::FieldCentric:
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...
 
FieldCentricWithVelocityX (units::meters_per_second_t velocityX)
 Sets the velocity in the X direction. More...
 
FieldCentricWithVelocityY (units::meters_per_second_t velocityY)
 Sets the velocity in the Y direction. More...
 
FieldCentricWithRotationalRate (units::radians_per_second_t rotationalRate)
 The angular rate to rotate at. More...
 
FieldCentricWithDeadband (units::meters_per_second_t deadband)
 Sets the allowable deadband of the request. More...
 
FieldCentricWithRotationalDeadband (units::radians_per_second_t rotationalDeadband)
 Sets the rotational deadband of the request. More...
 
FieldCentricWithCenterOfRotation (Translation2d centerOfRotation)
 Sets the center of rotation of the request. More...
 
FieldCentricWithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType driveRequestType)
 Sets the type of control request to use for the drive motor. More...
 
FieldCentricWithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType steerRequestType)
 Sets the type of control request to use for the steer motor. More...
 
FieldCentricWithDesaturateWheelSpeeds (bool desaturateWheelSpeeds)
 Sets whether to desaturate wheel speeds before applying. More...
 
FieldCentricWithForwardReference (ForwardReferenceValue forwardReference)
 Sets the perspective to use when determining which direction is forward. 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

units::meters_per_second_t VelocityX = 0_mps
 The velocity in the X direction. More...
 
units::meters_per_second_t VelocityY = 0_mps
 The velocity in the Y direction. More...
 
units::radians_per_second_t RotationalRate = 0_rad_per_s
 The angular rate to rotate at. More...
 
units::meters_per_second_t Deadband = 0_mps
 The allowable deadband of the request. More...
 
units::radians_per_second_t RotationalDeadband = 0_rad_per_s
 The rotational deadband of the request. More...
 
Translation2d CenterOfRotation {}
 The center of rotation the robot should 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...
 
ForwardReferenceValue ForwardReference = ForwardReferenceValue::OperatorPerspective
 The perspective to use when determining which direction is forward. More...
 

Additional Inherited Members

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

Detailed Description

Drives the swerve drivetrain in a field-centric manner.

When users use this request, they specify the direction the robot should travel oriented against the field, and the rate at which their robot should rotate about the center of the robot.

An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and RotationRate is 0.5 rad/s. In this scenario, the robot would drive northward at 5 m/s and turn counterclockwise at 0.5 rad/s.

Member Function Documentation

◆ Apply()

ctre::phoenix::StatusCode ctre::phoenix6::swerve::requests::FieldCentric::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()

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

Sets the center of rotation of the request.

Parameters
centerOfRotationThe center of rotation the robot should rotate around.
Returns
this request

◆ WithDeadband()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithDeadband ( units::meters_per_second_t  deadband)
inline

Sets the allowable deadband of the request.

Parameters
deadbandAllowable deadband of the request
Returns
this request

◆ WithDesaturateWheelSpeeds()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::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()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::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

◆ WithForwardReference()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithForwardReference ( ForwardReferenceValue  forwardReference)
inline

Sets the perspective to use when determining which direction is forward.

Parameters
desaturateWheelSpeedsThe perspective to use when determining which direction is forward
Returns
this request

◆ WithRotationalDeadband()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithRotationalDeadband ( units::radians_per_second_t  rotationalDeadband)
inline

Sets the rotational deadband of the request.

Parameters
rotationalDeadbandRotational deadband of the request
Returns
this request

◆ WithRotationalRate()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithRotationalRate ( units::radians_per_second_t  rotationalRate)
inline

The angular rate to rotate at.

Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

Parameters
rotationalRateAngular rate to rotate at
Returns
this request

◆ WithSteerRequestType()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::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

◆ WithVelocityX()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithVelocityX ( units::meters_per_second_t  velocityX)
inline

Sets the velocity in the X direction.

X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters
velocityXVelocity in the X direction
Returns
this request

◆ WithVelocityY()

FieldCentric & ctre::phoenix6::swerve::requests::FieldCentric::WithVelocityY ( units::meters_per_second_t  velocityY)
inline

Sets the velocity in the Y direction.

Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.

Parameters
velocityYVelocity in the Y direction
Returns
this request

Member Data Documentation

◆ CenterOfRotation

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

The center of rotation the robot should rotate around.

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

◆ Deadband

units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentric::Deadband = 0_mps

The allowable deadband of the request.

◆ DesaturateWheelSpeeds

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

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

◆ ForwardReference

ForwardReferenceValue ctre::phoenix6::swerve::requests::FieldCentric::ForwardReference = ForwardReferenceValue::OperatorPerspective

The perspective to use when determining which direction is forward.

◆ RotationalDeadband

units::radians_per_second_t ctre::phoenix6::swerve::requests::FieldCentric::RotationalDeadband = 0_rad_per_s

The rotational deadband of the request.

◆ RotationalRate

units::radians_per_second_t ctre::phoenix6::swerve::requests::FieldCentric::RotationalRate = 0_rad_per_s

The angular rate to rotate at.

Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.

◆ SteerRequestType

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

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

◆ VelocityX

units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentric::VelocityX = 0_mps

The velocity in the X direction.

X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

◆ VelocityY

units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentric::VelocityY = 0_mps

The velocity in the Y direction.

Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.


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