Class SwerveRequest.FieldCentricFacingAngle
java.lang.Object
com.ctre.phoenix6.mechanisms.swerve.SwerveRequest.FieldCentricFacingAngle
- All Implemented Interfaces:
SwerveRequest
- Enclosing interface:
- SwerveRequest
public static class SwerveRequest.FieldCentricFacingAngle extends Object implements SwerveRequest
Drives the swerve drivetrain in a field-centric manner, maintaining a
specified heading
angle to ensure the robot is facing the desired direction
When users use this request, they specify the direction the robot should travel oriented against the field, and the direction the robot should be facing.
An example scenario is that the robot is oriented to the east, the VelocityX is +5 m/s, VelocityY is 0 m/s, and TargetDirection is 180 degrees. In this scenario, the robot would drive northward at 5 m/s and turn clockwise to a target of 180 degrees.
This control request is especially useful for autonomous control, where the robot should be facing a changing direction throughout the motion.
-
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.PhoenixPIDController
HeadingController
The PID controller used to maintain the desired heading.double
RotationalDeadband
The rotational deadband of the request.SwerveModule.SteerRequestType
SteerRequestType
The type of control request to use for the steer motor.Rotation2d
TargetDirection
The desired direction to face.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 FieldCentricFacingAngle()
-
Method Summary
Modifier and Type Method Description StatusCode
apply(SwerveRequest.SwerveControlRequestParameters parameters, SwerveModule... modulesToApply)
Applies this swerve request to the given modules.SwerveRequest.FieldCentricFacingAngle
withCenterOfRotation(Translation2d centerOfRotation)
Sets the center of rotation of the requestSwerveRequest.FieldCentricFacingAngle
withDeadband(double deadband)
Sets the allowable deadband of the request.SwerveRequest.FieldCentricFacingAngle
withDriveRequestType(SwerveModule.DriveRequestType driveRequestType)
Sets the type of control request to use for the drive motor.SwerveRequest.FieldCentricFacingAngle
withRotationalDeadband(double rotationalDeadband)
Sets the rotational deadband of the request.SwerveRequest.FieldCentricFacingAngle
withSteerRequestType(SwerveModule.SteerRequestType steerRequestType)
Sets the type of control request to use for the steer motor.SwerveRequest.FieldCentricFacingAngle
withTargetDirection(Rotation2d targetDirection)
Sets the desired direction to face.SwerveRequest.FieldCentricFacingAngle
withVelocityX(double velocityX)
Sets the velocity in the X direction, in m/s.SwerveRequest.FieldCentricFacingAngle
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. -
TargetDirection
The desired direction to face. 0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left. -
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. -
HeadingController
The PID controller used to maintain the desired heading. Users can specify the PID gains to change how aggressively to maintain heading.This PID controller operates on heading radians and outputs a target rotational rate in radians per second.
-
ForwardReference
The perspective to use when determining which direction is forward.
-
-
Constructor Details
-
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
-
withTargetDirection
Sets the desired direction to face. 0 Degrees is defined as in the direction of the X axis. As a result, a TargetDirection of 90 degrees will point along the Y axis, or to the left.- Parameters:
targetDirection
- Desired direction to face- 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.FieldCentricFacingAngle 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.FieldCentricFacingAngle 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
-