CTRE Phoenix 6 C++ 25.0.0-beta-4
|
Drives the swerve drivetrain in a robot-centric manner. 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. | |
RobotCentric & | WithVelocityX (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. | |
RobotCentric & | WithVelocityY (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. | |
RobotCentric & | WithRotationalRate (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. | |
RobotCentric & | WithDeadband (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. | |
RobotCentric & | WithRotationalDeadband (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. | |
RobotCentric & | WithCenterOfRotation (Translation2d newCenterOfRotation) & |
Modifies the CenterOfRotation parameter and returns itself. | |
RobotCentric && | WithCenterOfRotation (Translation2d newCenterOfRotation) && |
Modifies the CenterOfRotation parameter and returns itself. | |
RobotCentric & | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) & |
Modifies the DriveRequestType parameter and returns itself. | |
RobotCentric && | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) && |
Modifies the DriveRequestType parameter and returns itself. | |
RobotCentric & | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) & |
Modifies the DriveRequestType parameter and returns itself. | |
RobotCentric && | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) && |
Modifies the DriveRequestType parameter and returns itself. | |
RobotCentric & | WithDesaturateWheelSpeeds (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 |
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.
|
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 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 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 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 DriveRequestType parameter and returns itself.
The type of control request to use for the drive motor.
newDriveRequestType | Parameter to modify |
|
inline |
Modifies the RotationalDeadband parameter and returns itself.
The rotational deadband of the request.
newRotationalDeadband | Parameter to modify |
|
inline |
Modifies the RotationalDeadband parameter and returns itself.
The rotational deadband of the request.
newRotationalDeadband | Parameter to modify |
|
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.
newRotationalRate | Parameter to modify |
|
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.
newRotationalRate | Parameter to modify |
|
inline |
Modifies the DriveRequestType parameter and returns itself.
The type of control request to use for the steer motor.
newSteerRequestType | Parameter to modify |
|
inline |
Modifies the DriveRequestType parameter and returns itself.
The type of control request to use for the steer motor.
newSteerRequestType | 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 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 |
|
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::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.
units::meters_per_second_t ctre::phoenix6::swerve::requests::RobotCentric::Deadband = 0_mps |
The allowable deadband of the request.
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.
impl::SwerveModuleImpl::DriveRequestType ctre::phoenix6::swerve::requests::RobotCentric::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage |
The type of control request to use for the drive motor.
units::radians_per_second_t ctre::phoenix6::swerve::requests::RobotCentric::RotationalDeadband = 0_rad_per_s |
The rotational deadband of the request.
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.
impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::RobotCentric::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::Position |
The type of control request to use for the steer motor.
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.
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.