CTRE Phoenix 6 C++ 25.3.1
Loading...
Searching...
No Matches
ctre::phoenix6::swerve::requests::RobotCentricFacingAngle Class Reference

Drives the swerve drivetrain in a robot-centric manner, maintaining a specified heading angle to ensure the robot is facing the desired direction. More...

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

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

Public Member Functions

 RobotCentricFacingAngle ()
 
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.
 
RobotCentricFacingAngleWithHeadingPID (double kP, double kI, double kD)
 Modifies the PID gains of the HeadingController parameter and returns itself.
 
RobotCentricFacingAngleWithVelocityX (units::meters_per_second_t newVelocityX)
 Modifies the VelocityX parameter and returns itself.
 
RobotCentricFacingAngleWithVelocityY (units::meters_per_second_t newVelocityY)
 Modifies the VelocityY parameter and returns itself.
 
RobotCentricFacingAngleWithTargetDirection (Rotation2d newTargetDirection)
 Modifies the VelocityY parameter and returns itself.
 
RobotCentricFacingAngleWithTargetRateFeedforward (units::radians_per_second_t newTargetRateFeedforward)
 Modifies the VelocityY parameter and returns itself.
 
RobotCentricFacingAngleWithDeadband (units::meters_per_second_t newDeadband)
 Modifies the Deadband parameter and returns itself.
 
RobotCentricFacingAngleWithRotationalDeadband (units::radians_per_second_t newRotationalDeadband)
 Modifies the RotationalDeadband parameter and returns itself.
 
RobotCentricFacingAngleWithMaxAbsRotationalRate (units::radians_per_second_t newMaxAbsRotationalRate)
 Modifies the MaxAbsRotationalRate parameter and returns itself.
 
RobotCentricFacingAngleWithCenterOfRotation (Translation2d newCenterOfRotation)
 Modifies the CenterOfRotation parameter and returns itself.
 
RobotCentricFacingAngleWithDriveRequestType (impl::DriveRequestType newDriveRequestType)
 Modifies the DriveRequestType parameter and returns itself.
 
RobotCentricFacingAngleWithSteerRequestType (impl::SteerRequestType newSteerRequestType)
 Modifies the SteerRequestType parameter and returns itself.
 
RobotCentricFacingAngleWithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds)
 Modifies the DesaturateWheelSpeeds parameter and returns itself.
 
RobotCentricFacingAngleWithForwardPerspective (ForwardPerspectiveValue newForwardPerspective)
 Modifies the ForwardPerspective 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.
 
Rotation2d TargetDirection {}
 The desired direction to face.
 
units::radians_per_second_t TargetRateFeedforward = 0_rad_per_s
 The rotational rate feedforward to add to the output of the heading controller, in radians per second.
 
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.
 
units::radians_per_second_t MaxAbsRotationalRate = 0_rad_per_s
 The maximum absolute rotational rate to allow.
 
Translation2d CenterOfRotation {}
 The center of rotation the robot should rotate around.
 
impl::DriveRequestType DriveRequestType = impl::DriveRequestType::OpenLoopVoltage
 The type of control request to use for the drive motor.
 
impl::SteerRequestType SteerRequestType = impl::SteerRequestType::Position
 The type of control request to use for the steer motor.
 
bool DesaturateWheelSpeeds = true
 Whether to desaturate wheel speeds before applying.
 
ForwardPerspectiveValue ForwardPerspective = ForwardPerspectiveValue::OperatorPerspective
 The perspective to use when determining which direction is forward for the target heading.
 
PhoenixPIDController HeadingController {0, 0, 0}
 The PID controller used to maintain the desired heading.
 

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, maintaining a specified heading angle to ensure the robot is facing the desired direction.

When users use this request, they specify the direction the robot should travel oriented against the robot itself, and the direction the robot should be facing relative to the field.

An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. In this scenario, the robot would drive forward at 5 m/s and turn clockwise to a target of 180 degrees.

This control request is especially useful for vision control, where the robot should be facing a vision target throughout the motion.

Constructor & Destructor Documentation

◆ RobotCentricFacingAngle()

ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::RobotCentricFacingAngle ( )
inline

Member Function Documentation

◆ Apply()

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

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

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

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

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithDriveRequestType ( impl::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

◆ WithForwardPerspective()

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithForwardPerspective ( ForwardPerspectiveValue newForwardPerspective)
inline

Modifies the ForwardPerspective parameter and returns itself.

The perspective to use when determining which direction is forward for the target heading.

Parameters
newForwardPerspectiveParameter to modify
Returns
this object

◆ WithHeadingPID()

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithHeadingPID ( double kP,
double kI,
double kD )
inline

Modifies the PID gains of the HeadingController parameter and returns itself.

Sets the proportional, integral, and differential coefficients used to maintain the desired heading. Users can specify the PID gains to change how aggressively to maintain heading.

This PID controller operates on heading radians and outputs a target rotational rate in radians per second.

Parameters
kPThe proportional coefficient; must be >= 0
kIThe integral coefficient; must be >= 0
kDThe differential coefficient; must be >= 0
Returns
this object

◆ WithMaxAbsRotationalRate()

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithMaxAbsRotationalRate ( units::radians_per_second_t newMaxAbsRotationalRate)
inline

Modifies the MaxAbsRotationalRate parameter and returns itself.

The maximum absolute rotational rate to allow. Setting this to 0 results in no cap to rotational rate.

Parameters
newMaxAbsRotationalRateParameter to modify
Returns
this object

◆ WithRotationalDeadband()

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

◆ WithSteerRequestType()

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

Modifies the SteerRequestType parameter and returns itself.

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

Parameters
newSteerRequestTypeParameter to modify
Returns
this object

◆ WithTargetDirection()

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithTargetDirection ( Rotation2d newTargetDirection)
inline

Modifies the VelocityY parameter and returns itself.

The desired direction to face. 0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left.

Parameters
newTargetDirectionParameter to modify
Returns
this object

◆ WithTargetRateFeedforward()

RobotCentricFacingAngle & ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::WithTargetRateFeedforward ( units::radians_per_second_t newTargetRateFeedforward)
inline

Modifies the VelocityY parameter and returns itself.

The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

Parameters
newTargetRateFeedforwardParameter to modify
Returns
this object

◆ WithVelocityX()

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

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

The allowable deadband of the request.

◆ DesaturateWheelSpeeds

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

Whether to desaturate wheel speeds before applying.

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

◆ DriveRequestType

impl::DriveRequestType ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::DriveRequestType = impl::DriveRequestType::OpenLoopVoltage

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

◆ ForwardPerspective

ForwardPerspectiveValue ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::ForwardPerspective = ForwardPerspectiveValue::OperatorPerspective

The perspective to use when determining which direction is forward for the target heading.

◆ HeadingController

PhoenixPIDController ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::HeadingController {0, 0, 0}

The PID controller used to maintain the desired heading.

Users can specify the PID gains to change how aggressively to maintain heading.

This PID controller operates on heading radians and outputs a target rotational rate in radians per second. Note that continuous input should be enabled on the range [-pi, pi].

◆ MaxAbsRotationalRate

units::radians_per_second_t ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::MaxAbsRotationalRate = 0_rad_per_s

The maximum absolute rotational rate to allow.

Setting this to 0 results in no cap to rotational rate.

◆ RotationalDeadband

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

The rotational deadband of the request.

◆ SteerRequestType

impl::SteerRequestType ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::SteerRequestType = impl::SteerRequestType::Position

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

◆ TargetDirection

Rotation2d ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::TargetDirection {}

The desired direction to face.

0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left.

◆ TargetRateFeedforward

units::radians_per_second_t ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::TargetRateFeedforward = 0_rad_per_s

The rotational rate feedforward to add to the output of the heading controller, in radians per second.

When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

◆ VelocityX

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