CTRE Phoenix 6 C++ 25.0.0-beta-4
|
Accepts a generic robot-centric 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. | |
ApplyRobotSpeeds & | WithSpeeds (ChassisSpeeds newSpeeds) & |
Modifies the Speeds parameter and returns itself. | |
ApplyRobotSpeeds && | WithSpeeds (ChassisSpeeds newSpeeds) && |
Modifies the Speeds parameter and returns itself. | |
ApplyRobotSpeeds & | WithWheelForceFeedforwardsX (std::vector< units::newton_t > newWheelForceFeedforwardsX) & |
Modifies the WheelForceFeedforwardsX parameter and returns itself. | |
ApplyRobotSpeeds && | WithWheelForceFeedforwardsX (std::vector< units::newton_t > newWheelForceFeedforwardsX) && |
Modifies the WheelForceFeedforwardsX parameter and returns itself. | |
ApplyRobotSpeeds & | WithWheelForceFeedforwardsY (std::vector< units::newton_t > newWheelForceFeedforwardsY) & |
Modifies the WheelForceFeedforwardsY parameter and returns itself. | |
ApplyRobotSpeeds && | WithWheelForceFeedforwardsY (std::vector< units::newton_t > newWheelForceFeedforwardsY) && |
Modifies the WheelForceFeedforwardsY parameter and returns itself. | |
ApplyRobotSpeeds & | WithCenterOfRotation (Translation2d newCenterOfRotation) & |
Modifies the CenterOfRotation parameter and returns itself. | |
ApplyRobotSpeeds && | WithCenterOfRotation (Translation2d newCenterOfRotation) && |
Modifies the CenterOfRotation parameter and returns itself. | |
ApplyRobotSpeeds & | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) & |
Modifies the DriveRequestType parameter and returns itself. | |
ApplyRobotSpeeds && | WithDriveRequestType (impl::SwerveModuleImpl::DriveRequestType newDriveRequestType) && |
Modifies the DriveRequestType parameter and returns itself. | |
ApplyRobotSpeeds & | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) & |
Modifies the DriveRequestType parameter and returns itself. | |
ApplyRobotSpeeds && | WithSteerRequestType (impl::SwerveModuleImpl::SteerRequestType newSteerRequestType) && |
Modifies the DriveRequestType parameter and returns itself. | |
ApplyRobotSpeeds & | WithDesaturateWheelSpeeds (bool newDesaturateWheelSpeeds) & |
Modifies the DesaturateWheelSpeeds parameter and returns itself. | |
ApplyRobotSpeeds && | 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 | |
ChassisSpeeds | Speeds {} |
The robot-centric chassis speeds to apply to the drivetrain. | |
std::vector< units::newton_t > | WheelForceFeedforwardsX |
Robot-centric wheel force feedforwards to apply in the X direction. | |
std::vector< units::newton_t > | WheelForceFeedforwardsY |
Robot-centric wheel force feedforwards to apply in the Y direction. | |
Translation2d | CenterOfRotation {} |
The center of rotation to 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 |
Accepts a generic robot-centric 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 |
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 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 Speeds parameter and returns itself.
The robot-centric chassis speeds to apply to the drivetrain.
newSpeeds | Parameter to modify |
|
inline |
Modifies the Speeds parameter and returns itself.
The robot-centric chassis speeds to apply to the drivetrain.
newSpeeds | 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 WheelForceFeedforwardsX parameter and returns itself.
Robot-centric wheel force feedforwards to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.
newWheelForceFeedforwardsX | Parameter to modify |
|
inline |
Modifies the WheelForceFeedforwardsX parameter and returns itself.
Robot-centric wheel force feedforwards to apply in the X direction. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.
newWheelForceFeedforwardsX | Parameter to modify |
|
inline |
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Robot-centric wheel force feedforwards to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.
newWheelForceFeedforwardsY | Parameter to modify |
|
inline |
Modifies the WheelForceFeedforwardsY parameter and returns itself.
Robot-centric wheel force feedforwards to apply in the Y direction. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.
newWheelForceFeedforwardsY | Parameter to modify |
Translation2d ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::CenterOfRotation {} |
The center of rotation to rotate around.
bool ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::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::ApplyRobotSpeeds::DriveRequestType = impl::SwerveModuleImpl::DriveRequestType::OpenLoopVoltage |
The type of control request to use for the drive motor.
ChassisSpeeds ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::Speeds {} |
The robot-centric chassis speeds to apply to the drivetrain.
impl::SwerveModuleImpl::SteerRequestType ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::SteerRequestType = impl::SwerveModuleImpl::SteerRequestType::Position |
The type of control request to use for the steer motor.
std::vector<units::newton_t> ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WheelForceFeedforwardsX |
Robot-centric wheel force feedforwards to apply in the X direction.
X is defined as forward according to WPILib convention, so this determines the forward forces to apply.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.
std::vector<units::newton_t> ctre::phoenix6::swerve::requests::ApplyRobotSpeeds::WheelForceFeedforwardsY |
Robot-centric wheel force feedforwards to apply in the Y direction.
Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.
These forces should include friction applied to the ground.
The order of the forces should match the order of the modules returned from SwerveDrivetrain.