CTRE Phoenix 6 C++ 24.50.0-alpha-2
|
Drives the swerve drivetrain in a field-centric manner, maintaining a specified heading angle to ensure the robot is facing the desired direction. More...
#include <ctre/phoenix6/swerve/SwerveRequest.hpp>
Public Member Functions | |
ctre::phoenix::StatusCode | Apply (SwerveRequest::ControlParameters const ¶meters, std::vector< std::unique_ptr< impl::SwerveModuleImpl > > const &modulesToApply) override |
Applies this swerve request to the given modules. More... | |
FieldCentricFacingAngle & | WithVelocityX (units::meters_per_second_t velocityX) |
Sets the velocity in the X direction. More... | |
FieldCentricFacingAngle & | WithVelocityY (units::meters_per_second_t velocityY) |
Sets the velocity in the Y direction. More... | |
FieldCentricFacingAngle & | WithTargetDirection (Rotation2d targetDirection) |
Sets the desired direction to face. More... | |
FieldCentricFacingAngle & | WithDeadband (units::meters_per_second_t deadband) |
Sets the allowable deadband of the request. More... | |
FieldCentricFacingAngle & | WithRotationalDeadband (units::radians_per_second_t rotationalDeadband) |
Sets the rotational deadband of the request. More... | |
FieldCentricFacingAngle & | WithCenterOfRotation (Translation2d centerOfRotation) |
Sets the center of rotation of the request. More... | |
FieldCentricFacingAngle & | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType driveRequestType) |
Sets the type of control request to use for the drive motor. More... | |
FieldCentricFacingAngle & | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType steerRequestType) |
Sets the type of control request to use for the steer motor. More... | |
FieldCentricFacingAngle & | WithDesaturateWheelSpeeds (bool desaturateWheelSpeeds) |
Sets whether to desaturate wheel speeds before applying. More... | |
FieldCentricFacingAngle & | WithForwardReference (ForwardReferenceValue forwardReference) |
Sets the perspective to use when determining which direction is forward. More... | |
![]() | |
virtual | ~SwerveRequest ()=default |
virtual ctre::phoenix::StatusCode | Apply (ControlParameters const ¶meters, 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... | |
Rotation2d | TargetDirection {} |
The desired direction to face. 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... | |
PhoenixPIDController | HeadingController {0, 0, 0} |
The PID controller used to maintain the desired heading. More... | |
Additional Inherited Members | |
![]() | |
using | ControlParameters = impl::SwerveDrivetrainImpl::ControlParameters |
Drives the swerve drivetrain in a field-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 field, and the direction the robot should be facing.
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 northward at 5 m/s and turn clockwise to a target of 180 degrees.
This control request is especially useful for autonomous control, where the robot should be facing a changing direction throughout the motion.
|
inlineoverridevirtual |
Applies this swerve request to the given modules.
This is typically called by the SwerveDrivetrain.
parameters | Parameters the control request needs to calculate the module state |
modulesToApply | Modules to which the control request is applied |
Implements ctre::phoenix6::swerve::requests::SwerveRequest.
|
inline |
Sets the center of rotation of the request.
centerOfRotation | The center of rotation the robot should rotate around. |
|
inline |
Sets the allowable deadband of the request.
deadband | Allowable deadband of the request |
|
inline |
Sets whether to desaturate wheel speeds before applying.
For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.
desaturateWheelSpeeds | Whether to desaturate wheel speeds |
|
inline |
Sets the type of control request to use for the drive motor.
driveRequestType | The type of control request to use for the drive motor |
|
inline |
Sets the perspective to use when determining which direction is forward.
desaturateWheelSpeeds | The perspective to use when determining which direction is forward |
|
inline |
Sets the rotational deadband of the request.
rotationalDeadband | Rotational deadband of the request |
|
inline |
Sets the type of control request to use for the steer motor.
steerRequestType | The type of control request to use for the steer motor |
|
inline |
Sets 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.
targetDirection | Desired direction to face |
|
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.
velocityX | Velocity in the X direction |
|
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.
velocityY | Velocity in the Y direction |
Translation2d ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::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.
units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::Deadband = 0_mps |
The allowable deadband of the request.
bool ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::DesaturateWheelSpeeds = true |
Whether to desaturate wheel speeds before applying.
For more information, see the documentation of impl::SwerveDriveKinematics::DesaturateWheelSpeeds.
impl::SwerveModuleImpl::DriveRequestType ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage |
The type of control request to use for the drive motor.
ForwardReferenceValue ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::ForwardReference = ForwardReferenceValue::OperatorPerspective |
The perspective to use when determining which direction is forward.
PhoenixPIDController ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::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.
units::radians_per_second_t ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::RotationalDeadband = 0_rad_per_s |
The rotational deadband of the request.
impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::MotionMagicExpo |
The type of control request to use for the steer motor.
Rotation2d ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::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.
units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::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.
units::meters_per_second_t ctre::phoenix6::swerve::requests::FieldCentricFacingAngle::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.