CTRE Phoenix 6 C++ 25.3.1
|
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>
Public Member Functions | |
RobotCentricFacingAngle () | |
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. | |
RobotCentricFacingAngle & | WithHeadingPID (double kP, double kI, double kD) |
Modifies the PID gains of the HeadingController parameter and returns itself. | |
RobotCentricFacingAngle & | WithVelocityX (units::meters_per_second_t newVelocityX) |
Modifies the VelocityX parameter and returns itself. | |
RobotCentricFacingAngle & | WithVelocityY (units::meters_per_second_t newVelocityY) |
Modifies the VelocityY parameter and returns itself. | |
RobotCentricFacingAngle & | WithTargetDirection (Rotation2d newTargetDirection) |
Modifies the VelocityY parameter and returns itself. | |
RobotCentricFacingAngle & | WithTargetRateFeedforward (units::radians_per_second_t newTargetRateFeedforward) |
Modifies the VelocityY parameter and returns itself. | |
RobotCentricFacingAngle & | WithDeadband (units::meters_per_second_t newDeadband) |
Modifies the Deadband parameter and returns itself. | |
RobotCentricFacingAngle & | WithRotationalDeadband (units::radians_per_second_t newRotationalDeadband) |
Modifies the RotationalDeadband parameter and returns itself. | |
RobotCentricFacingAngle & | WithMaxAbsRotationalRate (units::radians_per_second_t newMaxAbsRotationalRate) |
Modifies the MaxAbsRotationalRate parameter and returns itself. | |
RobotCentricFacingAngle & | WithCenterOfRotation (Translation2d newCenterOfRotation) |
Modifies the CenterOfRotation parameter and returns itself. | |
RobotCentricFacingAngle & | WithDriveRequestType (impl::DriveRequestType newDriveRequestType) |
Modifies the DriveRequestType parameter and returns itself. | |
RobotCentricFacingAngle & | WithSteerRequestType (impl::SteerRequestType newSteerRequestType) |
Modifies the SteerRequestType parameter and returns itself. | |
RobotCentricFacingAngle & | WithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds) |
Modifies the DesaturateWheelSpeeds parameter and returns itself. | |
RobotCentricFacingAngle & | WithForwardPerspective (ForwardPerspectiveValue newForwardPerspective) |
Modifies the ForwardPerspective parameter and returns itself. | |
![]() | |
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 | |
![]() | |
using | ControlParameters = impl::SwerveDrivetrainImpl::ControlParameters |
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.
|
inline |
|
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 |
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.
newCenterOfRotation | Parameter to modify |
|
inline |
Modifies the Deadband parameter and returns itself.
The allowable deadband of the request.
newDeadband | Parameter to modify |
|
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.
newDesaturateWheelSpeeds | Parameter to modify |
|
inline |
Modifies the DriveRequestType parameter and returns itself.
The type of control request to use for the drive motor.
newDriveRequestType | Parameter to modify |
|
inline |
Modifies the ForwardPerspective parameter and returns itself.
The perspective to use when determining which direction is forward for the target heading.
newForwardPerspective | Parameter to modify |
|
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.
kP | The proportional coefficient; must be >= 0 |
kI | The integral coefficient; must be >= 0 |
kD | The differential coefficient; must be >= 0 |
|
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.
newMaxAbsRotationalRate | Parameter to modify |
|
inline |
Modifies the RotationalDeadband parameter and returns itself.
The rotational deadband of the request.
newRotationalDeadband | Parameter to modify |
|
inline |
Modifies the SteerRequestType parameter and returns itself.
The type of control request to use for the steer motor.
newSteerRequestType | Parameter to modify |
|
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.
newTargetDirection | Parameter to modify |
|
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.
newTargetRateFeedforward | Parameter to modify |
|
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.
newVelocityX | Parameter to modify |
|
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.
newVelocityY | Parameter to modify |
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.
units::meters_per_second_t ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::Deadband = 0_mps |
The allowable deadband of the request.
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.
impl::DriveRequestType ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::DriveRequestType = impl::DriveRequestType::OpenLoopVoltage |
The type of control request to use for the drive motor.
ForwardPerspectiveValue ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::ForwardPerspective = ForwardPerspectiveValue::OperatorPerspective |
The perspective to use when determining which direction is forward for the target heading.
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].
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.
units::radians_per_second_t ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::RotationalDeadband = 0_rad_per_s |
The rotational deadband of the request.
impl::SteerRequestType ctre::phoenix6::swerve::requests::RobotCentricFacingAngle::SteerRequestType = impl::SteerRequestType::Position |
The type of control request to use for the steer motor.
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.
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.
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.
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.