CTRE Phoenix 6 C++ 24.50.0-alpha-2
|
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. More... | |
RobotCentric & | WithVelocityX (units::meters_per_second_t velocityX) |
Sets the velocity in the X direction. More... | |
RobotCentric & | WithVelocityY (units::meters_per_second_t velocityY) |
Sets the velocity in the Y direction. More... | |
RobotCentric & | WithRotationalRate (units::radians_per_second_t rotationalRate) |
The angular rate to rotate at. More... | |
RobotCentric & | WithDeadband (units::meters_per_second_t deadband) |
Sets the allowable deadband of the request. More... | |
RobotCentric & | WithRotationalDeadband (units::radians_per_second_t rotationalDeadband) |
Sets the rotational deadband of the request. More... | |
RobotCentric & | WithCenterOfRotation (Translation2d centerOfRotation) |
Sets the center of rotation of the request. More... | |
RobotCentric & | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType driveRequestType) |
Sets the type of control request to use for the drive motor. More... | |
RobotCentric & | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType steerRequestType) |
Sets the type of control request to use for the steer motor. More... | |
RobotCentric & | WithDesaturateWheelSpeeds (bool desaturateWheelSpeeds) |
Sets whether to desaturate wheel speeds before applying. 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... | |
units::radians_per_second_t | RotationalRate = 0_rad_per_s |
The angular rate to rotate at. 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... | |
Additional Inherited Members | |
![]() | |
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 |
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 rotational deadband of the request.
rotationalDeadband | Rotational deadband of the request |
|
inline |
The angular rate to rotate at.
Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.
rotationalRate | Angular rate to rotate at |
|
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 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::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::MotionMagicExpo |
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 to WPILib 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.