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

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

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

Inheritance diagram for ctre::phoenix6::swerve::requests::RobotCentric:
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.
 
RobotCentricWithVelocityX (units::meters_per_second_t newVelocityX) &
 Modifies the VelocityX parameter and returns itself.
 
RobotCentric && WithVelocityX (units::meters_per_second_t newVelocityX) &&
 Modifies the VelocityX parameter and returns itself.
 
RobotCentricWithVelocityY (units::meters_per_second_t newVelocityY) &
 Modifies the VelocityY parameter and returns itself.
 
RobotCentric && WithVelocityY (units::meters_per_second_t newVelocityY) &&
 Modifies the VelocityY parameter and returns itself.
 
RobotCentricWithRotationalRate (units::radians_per_second_t newRotationalRate) &
 Modifies the RotationalRate parameter and returns itself.
 
RobotCentric && WithRotationalRate (units::radians_per_second_t newRotationalRate) &&
 Modifies the RotationalRate parameter and returns itself.
 
RobotCentricWithDeadband (units::meters_per_second_t newDeadband) &
 Modifies the Deadband parameter and returns itself.
 
RobotCentric && WithDeadband (units::meters_per_second_t newDeadband) &&
 Modifies the Deadband parameter and returns itself.
 
RobotCentricWithRotationalDeadband (units::radians_per_second_t newRotationalDeadband) &
 Modifies the RotationalDeadband parameter and returns itself.
 
RobotCentric && WithRotationalDeadband (units::radians_per_second_t newRotationalDeadband) &&
 Modifies the RotationalDeadband parameter and returns itself.
 
RobotCentricWithCenterOfRotation (Translation2d newCenterOfRotation) &
 Modifies the CenterOfRotation parameter and returns itself.
 
RobotCentric && WithCenterOfRotation (Translation2d newCenterOfRotation) &&
 Modifies the CenterOfRotation parameter and returns itself.
 
RobotCentricWithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &
 Modifies the DriveRequestType parameter and returns itself.
 
RobotCentric && WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) &&
 Modifies the DriveRequestType parameter and returns itself.
 
RobotCentricWithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &
 Modifies the DriveRequestType parameter and returns itself.
 
RobotCentric && WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) &&
 Modifies the DriveRequestType parameter and returns itself.
 
RobotCentricWithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds) &
 Modifies the DesaturateWheelSpeeds parameter and returns itself.
 
RobotCentric && 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

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

Drives the swerve drivetrain in a robot-centric manner.

When users use this request, they specify the direction the robot should travel oriented against the robot itself, 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 eastward at 5 m/s and turn counterclockwise at 0.5 rad/s.

Member Function Documentation

◆ Apply()

ctre::phoenix::StatusCode ctre::phoenix6::swerve::requests::RobotCentric::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]

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

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

◆ WithDeadband() [1/2]

RobotCentric & ctre::phoenix6::swerve::requests::RobotCentric::WithDeadband ( units::meters_per_second_t newDeadband) &
inline

Modifies the Deadband parameter and returns itself.

The allowable deadband of the request.

Parameters
newDeadbandParameter to modify
Returns
this object

◆ WithDeadband() [2/2]

RobotCentric && ctre::phoenix6::swerve::requests::RobotCentric::WithDeadband ( units::meters_per_second_t newDeadband) &&
inline

Modifies the Deadband parameter and returns itself.

The allowable deadband of the request.

Parameters
newDeadbandParameter to modify
Returns
this object

◆ WithDesaturateWheelSpeeds() [1/2]

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

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

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

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

◆ WithRotationalDeadband() [1/2]

RobotCentric & ctre::phoenix6::swerve::requests::RobotCentric::WithRotationalDeadband ( units::radians_per_second_t newRotationalDeadband) &
inline

Modifies the RotationalDeadband parameter and returns itself.

The rotational deadband of the request.

Parameters
newRotationalDeadbandParameter to modify
Returns
this object

◆ WithRotationalDeadband() [2/2]

RobotCentric && ctre::phoenix6::swerve::requests::RobotCentric::WithRotationalDeadband ( units::radians_per_second_t newRotationalDeadband) &&
inline

Modifies the RotationalDeadband parameter and returns itself.

The rotational deadband of the request.

Parameters
newRotationalDeadbandParameter to modify
Returns
this object

◆ WithRotationalRate() [1/2]

RobotCentric & ctre::phoenix6::swerve::requests::RobotCentric::WithRotationalRate ( units::radians_per_second_t newRotationalRate) &
inline

Modifies the RotationalRate parameter and returns itself.

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

Parameters
newRotationalRateParameter to modify
Returns
this object

◆ WithRotationalRate() [2/2]

RobotCentric && ctre::phoenix6::swerve::requests::RobotCentric::WithRotationalRate ( units::radians_per_second_t newRotationalRate) &&
inline

Modifies the RotationalRate parameter and returns itself.

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

Parameters
newRotationalRateParameter to modify
Returns
this object

◆ WithSteerRequestType() [1/2]

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

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

◆ WithVelocityX() [1/2]

RobotCentric & ctre::phoenix6::swerve::requests::RobotCentric::WithVelocityX ( units::meters_per_second_t newVelocityX) &
inline

Modifies the VelocityX parameter and returns itself.

The velocity in the X direction. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters
newVelocityXParameter to modify
Returns
this object

◆ WithVelocityX() [2/2]

RobotCentric && ctre::phoenix6::swerve::requests::RobotCentric::WithVelocityX ( units::meters_per_second_t newVelocityX) &&
inline

Modifies the VelocityX parameter and returns itself.

The velocity in the X direction. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.

Parameters
newVelocityXParameter to modify
Returns
this object

◆ WithVelocityY() [1/2]

RobotCentric & ctre::phoenix6::swerve::requests::RobotCentric::WithVelocityY ( units::meters_per_second_t newVelocityY) &
inline

Modifies the VelocityY parameter and returns itself.

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
newVelocityYParameter to modify
Returns
this object

◆ WithVelocityY() [2/2]

RobotCentric && ctre::phoenix6::swerve::requests::RobotCentric::WithVelocityY ( units::meters_per_second_t newVelocityY) &&
inline

Modifies the VelocityY parameter and returns itself.

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
newVelocityYParameter to modify
Returns
this object

Member Data Documentation

◆ CenterOfRotation

Translation2d ctre::phoenix6::swerve::requests::RobotCentric::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::RobotCentric::Deadband = 0_mps

The allowable deadband of the request.

◆ DesaturateWheelSpeeds

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

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

◆ RotationalDeadband

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

The rotational deadband of the request.

◆ RotationalRate

units::radians_per_second_t ctre::phoenix6::swerve::requests::RobotCentric::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::RobotCentric::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::Position

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

◆ VelocityX

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

The velocity in the X direction.

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

◆ VelocityY

units::meters_per_second_t ctre::phoenix6::swerve::requests::RobotCentric::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: