Class LegacySwerveRequest.ApplyChassisSpeeds
java.lang.Object
com.ctre.phoenix6.mechanisms.swerve.LegacySwerveRequest.ApplyChassisSpeeds
- All Implemented Interfaces:
LegacySwerveRequest
- Enclosing interface:
- LegacySwerveRequest
public static class LegacySwerveRequest.ApplyChassisSpeeds
extends Object
implements LegacySwerveRequest
Accepts a generic ChassisSpeeds to apply to the drivetrain.
-
Nested Class Summary
Nested classes/interfaces inherited from interface com.ctre.phoenix6.mechanisms.swerve.LegacySwerveRequest
LegacySwerveRequest.ApplyChassisSpeeds, LegacySwerveRequest.FieldCentric, LegacySwerveRequest.FieldCentricFacingAngle, LegacySwerveRequest.ForwardReference, LegacySwerveRequest.Idle, LegacySwerveRequest.LegacySwerveControlRequestParameters, LegacySwerveRequest.PointWheelsAt, LegacySwerveRequest.RobotCentric, LegacySwerveRequest.SwerveDriveBrake, LegacySwerveRequest.SysIdSwerveRotation, LegacySwerveRequest.SysIdSwerveSteerGains, LegacySwerveRequest.SysIdSwerveTranslation
-
Field Summary
Modifier and TypeFieldDescriptionThe center of rotation to rotate around.boolean
Whether to desaturate wheel speeds before applying.The type of control request to use for the drive motor.The chassis speeds to apply to the drivetrain.The type of control request to use for the steer motor. -
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionapply
(LegacySwerveRequest.LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) Applies this swerve request to the given modules.withCenterOfRotation
(Translation2d centerOfRotation) Sets the center of rotation to rotate around.withDesaturateWheelSpeeds
(boolean desaturateWheelSpeeds) Sets whether to desaturate wheel speeds before applying.withDriveRequestType
(LegacySwerveModule.DriveRequestType driveRequestType) Sets the type of control request to use for the drive motor.withSpeeds
(ChassisSpeeds speeds) Sets the chassis speeds to apply to the drivetrain.withSteerRequestType
(LegacySwerveModule.SteerRequestType steerRequestType) Sets the type of control request to use for the steer motor.
-
Field Details
-
Speeds
The chassis speeds to apply to the drivetrain. -
CenterOfRotation
The center of rotation to rotate around. -
DriveRequestType
The type of control request to use for the drive motor. -
SteerRequestType
The type of control request to use for the steer motor. -
DesaturateWheelSpeeds
Whether to desaturate wheel speeds before applying. For more information, see the documentation ofSwerveDriveKinematics.desaturateWheelSpeeds(edu.wpi.first.math.kinematics.SwerveModuleState[], double)
.
-
-
Constructor Details
-
ApplyChassisSpeeds
public ApplyChassisSpeeds()
-
-
Method Details
-
apply
public StatusCode apply(LegacySwerveRequest.LegacySwerveControlRequestParameters parameters, LegacySwerveModule... modulesToApply) Description copied from interface:LegacySwerveRequest
Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain.- Specified by:
apply
in interfaceLegacySwerveRequest
- Parameters:
parameters
- Parameters the control request needs to calculate the module statemodulesToApply
- Modules to which the control request is applied- Returns:
- Status code of sending the request
-
withSpeeds
Sets the chassis speeds to apply to the drivetrain.- Parameters:
speeds
- Chassis speeds to apply to the drivetrain- Returns:
- this request
-
withCenterOfRotation
Sets the center of rotation to rotate around.- Parameters:
centerOfRotation
- Center of rotation to rotate around- Returns:
- this request
-
withDriveRequestType
public LegacySwerveRequest.ApplyChassisSpeeds withDriveRequestType(LegacySwerveModule.DriveRequestType driveRequestType) Sets the type of control request to use for the drive motor.- Parameters:
driveRequestType
- The type of control request to use for the drive motor- Returns:
- this request
-
withSteerRequestType
public LegacySwerveRequest.ApplyChassisSpeeds withSteerRequestType(LegacySwerveModule.SteerRequestType steerRequestType) Sets the type of control request to use for the steer motor.- Parameters:
steerRequestType
- The type of control request to use for the steer motor- Returns:
- this request
-
withDesaturateWheelSpeeds
public LegacySwerveRequest.ApplyChassisSpeeds withDesaturateWheelSpeeds(boolean desaturateWheelSpeeds) Sets whether to desaturate wheel speeds before applying. For more information, see the documentation ofSwerveDriveKinematics.desaturateWheelSpeeds(edu.wpi.first.math.kinematics.SwerveModuleState[], double)
.- Parameters:
desaturateWheelSpeeds
- Whether to desaturate wheel speeds- Returns:
- this request
-