CTRE Phoenix 6 C++ 24.50.0-alpha-2
|
Accepts a generic ChassisSpeeds to apply to the drivetrain. 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... | |
ApplyChassisSpeeds & | WithSpeeds (impl::ChassisSpeeds speeds) |
Sets the chassis speeds to apply to the drivetrain. More... | |
ApplyChassisSpeeds & | WithCenterOfRotation (Translation2d centerOfRotation) |
Sets the center of rotation to rotate around. More... | |
ApplyChassisSpeeds & | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType driveRequestType) |
Sets the type of control request to use for the drive motor. More... | |
ApplyChassisSpeeds & | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType steerRequestType) |
Sets the type of control request to use for the steer motor. More... | |
ApplyChassisSpeeds & | 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 | |
impl::ChassisSpeeds | Speeds {} |
The chassis speeds to apply to the drivetrain. More... | |
Translation2d | CenterOfRotation {} |
The center of rotation to 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 |
Accepts a generic ChassisSpeeds to apply to the drivetrain.
|
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 to rotate around.
centerOfRotation | Center of rotation to rotate around |
|
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 chassis speeds to apply to the drivetrain.
speeds | Chassis speeds to apply to the drivetrain |
|
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 |
Translation2d ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::CenterOfRotation {} |
The center of rotation to rotate around.
bool ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::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::ApplyChassisSpeeds::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage |
The type of control request to use for the drive motor.
impl::ChassisSpeeds ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::Speeds {} |
The chassis speeds to apply to the drivetrain.
impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::ApplyChassisSpeeds::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::MotionMagicExpo |
The type of control request to use for the steer motor.