Class SwerveRequest.FieldCentric
java.lang.Object
com.ctre.phoenix6.mechanisms.swerve.SwerveRequest.FieldCentric
- All Implemented Interfaces:
SwerveRequest
- Enclosing interface:
- SwerveRequest
public static class SwerveRequest.FieldCentric extends Object implements SwerveRequest
Drives the swerve drivetrain in a field-centric manner.
When users use this request, they specify the direction the robot should travel oriented against the field, 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 northward at 5 m/s and turn counterclockwise at 0.5 rad/s.
-
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 the robot should rotate around.double
Deadband
The allowable deadband of the request.SwerveModule.DriveRequestType
DriveRequestType
The type of control request to use for the drive motor.SwerveRequest.ForwardReference
ForwardReference
The perspective to use when determining which direction is forward.protected SwerveModuleState[]
m_lastAppliedState
The last applied state in case we don't have anything to drive.double
RotationalDeadband
The rotational deadband of the request.double
RotationalRate
The angular rate to rotate at, in radians per second.SwerveModule.SteerRequestType
SteerRequestType
The type of control request to use for the steer motor.double
VelocityX
The velocity in the X direction, in m/s.double
VelocityY
The velocity in the Y direction, in m/s. -
Constructor Summary
Constructors Constructor Description FieldCentric()
-
Method Summary
Modifier and Type Method Description StatusCode
apply(SwerveRequest.SwerveControlRequestParameters parameters, SwerveModule... modulesToApply)
Applies this swerve request to the given modules.SwerveRequest.FieldCentric
withCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation of the requestSwerveRequest.FieldCentric
withDeadband(double deadband)
Sets the allowable deadband of the request.SwerveRequest.FieldCentric
withDriveRequestType(SwerveModule.DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.SwerveRequest.FieldCentric
withRotationalDeadband(double rotationalDeadband)
Sets the rotational deadband of the request.SwerveRequest.FieldCentric
withRotationalRate(double rotationalRate)
The angular rate to rotate at, in radians per second.SwerveRequest.FieldCentric
withSteerRequestType(SwerveModule.SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.SwerveRequest.FieldCentric
withVelocityX(double velocityX)
Sets the velocity in the X direction, in m/s.SwerveRequest.FieldCentric
withVelocityY(double velocityY)
Sets the velocity in the Y direction, in m/s.
-
Field Details
-
VelocityX
The velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward. -
VelocityY
The velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left. -
RotationalRate
The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise. -
Deadband
The allowable deadband of the request. -
RotationalDeadband
The rotational deadband of the request. -
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. -
DriveRequestType
The type of control request to use for the drive motor. -
SteerRequestType
The type of control request to use for the steer motor. -
ForwardReference
The perspective to use when determining which direction is forward. -
m_lastAppliedState
The last applied state in case we don't have anything to drive.
-
-
Constructor Details
-
FieldCentric
public FieldCentric()
-
-
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
-
withVelocityX
Sets the velocity in the X direction, in m/s. X is defined as forward according to WPILib convention, so this determines how fast to travel forward.- Parameters:
velocityX
- Velocity in the X direction, in m/s- Returns:
- this request
-
withVelocityY
Sets the velocity in the Y direction, in m/s. Y is defined as to the left according to WPILib convention, so this determines how fast to travel to the left.- Parameters:
velocityY
- Velocity in the Y direction, in m/s- Returns:
- this request
-
withRotationalRate
The angular rate to rotate at, in radians per second. Angular rate is defined as counterclockwise positive, so this determines how fast to turn counterclockwise.- Parameters:
rotationalRate
- Angular rate to rotate at, in radians per second- Returns:
- this request
-
withDeadband
Sets the allowable deadband of the request.- Parameters:
deadband
- Allowable deadband of the request- Returns:
- this request
-
withRotationalDeadband
Sets the rotational deadband of the request.- Parameters:
rotationalDeadband
- Rotational deadband of the request- Returns:
- this request
-
withCenterOfRotation
Sets the center of rotation of the request- Parameters:
centerOfRotation
- The center of rotation the robot should rotate around.- Returns:
- this request
-
withDriveRequestType
public SwerveRequest.FieldCentric 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.FieldCentric 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
-