Class SwerveRequest.ApplyChassisSpeeds
java.lang.Object
com.ctre.phoenix6.mechanisms.swerve.SwerveRequest.ApplyChassisSpeeds
- All Implemented Interfaces:
SwerveRequest
- Enclosing interface:
- SwerveRequest
public static class SwerveRequest.ApplyChassisSpeeds extends Object implements SwerveRequest
Accepts a generic ChassisSpeeds to apply to the drivetrain.
-
Nested Class Summary
Nested classes/interfaces inherited from interface com.ctre.phoenix6.mechanisms.swerve.SwerveRequest
SwerveRequest.ApplyChassisSpeeds, SwerveRequest.FieldCentric, SwerveRequest.FieldCentricFacingAngle, SwerveRequest.ForwardReference, SwerveRequest.Idle, SwerveRequest.PointWheelsAt, SwerveRequest.RobotCentric, SwerveRequest.SwerveControlRequestParameters, SwerveRequest.SwerveDriveBrake, SwerveRequest.SysIdSwerveRotation, SwerveRequest.SysIdSwerveSteerGains, SwerveRequest.SysIdSwerveTranslation
-
Field Summary
Fields Modifier and Type Field Description Translation2d
CenterOfRotation
The center of rotation to rotate around.SwerveModule.DriveRequestType
DriveRequestType
The type of control request to use for the drive motor.ChassisSpeeds
Speeds
The chassis speeds to apply to the drivetrain.SwerveModule.SteerRequestType
SteerRequestType
The type of control request to use for the steer motor. -
Constructor Summary
Constructors Constructor Description ApplyChassisSpeeds()
-
Method Summary
Modifier and Type Method Description StatusCode
apply(SwerveRequest.SwerveControlRequestParameters parameters, SwerveModule... modulesToApply)
Applies this swerve request to the given modules.SwerveRequest.ApplyChassisSpeeds
withCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation to rotate around.SwerveRequest.ApplyChassisSpeeds
withDriveRequestType(SwerveModule.DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.SwerveRequest.ApplyChassisSpeeds
withSpeeds(ChassisSpeeds speeds)
Sets the chassis speeds to apply to the drivetrain.SwerveRequest.ApplyChassisSpeeds
withSteerRequestType(SwerveModule.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.
-
-
Constructor Details
-
ApplyChassisSpeeds
public ApplyChassisSpeeds()
-
-
Method Details
-
apply
public StatusCode apply(SwerveRequest.SwerveControlRequestParameters parameters, SwerveModule... modulesToApply)Description copied from interface:SwerveRequest
Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain.- Specified by:
apply
in interfaceSwerveRequest
- 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 SwerveRequest.ApplyChassisSpeeds withDriveRequestType(SwerveModule.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 SwerveRequest.ApplyChassisSpeeds withSteerRequestType(SwerveModule.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
-