Class SwerveRequest.FieldCentricFacingAngle

java.lang.Object
com.ctre.phoenix6.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.

  • Field Details

    • VelocityX

      public double 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

      public double 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.
    • TargetRateFeedforward

      public double TargetRateFeedforward
      The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.
    • Deadband

      public double Deadband
      The allowable deadband of the request, in m/s.
    • RotationalDeadband

      public double RotationalDeadband
      The rotational deadband of the request, in radians per second.
    • 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.
    • DesaturateWheelSpeeds

      public boolean DesaturateWheelSpeeds
      Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds(edu.wpi.first.math.kinematics.SwerveModuleState[], double).
    • ForwardPerspective

      The perspective to use when determining which direction is forward.
    • 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. Note that continuous input should be enabled on the range [-pi, pi].

  • Constructor Details

  • Method Details

    • apply

      public StatusCode apply(SwerveDrivetrain.SwerveControlParameters parameters, SwerveModule... modulesToApply)
      Description copied from interface: SwerveRequest
      Applies this swerve request to the given modules. This is typically called by the SwerveDrivetrain odometry thread.

      For native swerve requests, this API can be called from a non-native request's apply to compose the two together.

      Specified by:
      apply in interface SwerveRequest
      Parameters:
      parameters - Parameters the control request needs to calculate the module state
      modulesToApply - Modules to which the control request is applied
      Returns:
      Status code of sending the request
    • withVelocityX

      Modifies the VelocityX parameter and returns itself.

      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:
      newVelocityX - Parameter to modify
      Returns:
      this object
    • withVelocityX

      public SwerveRequest.FieldCentricFacingAngle withVelocityX(edu.wpi.first.units.measure.LinearVelocity newVelocityX)
      Modifies the VelocityX parameter and returns itself.

      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:
      newVelocityX - Parameter to modify
      Returns:
      this object
    • withVelocityY

      Modifies the VelocityY parameter and returns itself.

      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:
      newVelocityY - Parameter to modify
      Returns:
      this object
    • withVelocityY

      public SwerveRequest.FieldCentricFacingAngle withVelocityY(edu.wpi.first.units.measure.LinearVelocity newVelocityY)
      Modifies the VelocityY parameter and returns itself.

      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:
      newVelocityY - Parameter to modify
      Returns:
      this object
    • withTargetDirection

      Modifies the TargetDirection parameter and returns itself.

      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:
      newTargetDirection - Parameter to modify
      Returns:
      this object
    • withTargetRateFeedforward

      public SwerveRequest.FieldCentricFacingAngle withTargetRateFeedforward(double newTargetRateFeedforward)
      Modifies the TargetRateFeedforward parameter and returns itself.

      The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

      Parameters:
      newTargetRateFeedforward - Parameter to modify
      Returns:
      this object
    • withTargetRateFeedforward

      public SwerveRequest.FieldCentricFacingAngle withTargetRateFeedforward(edu.wpi.first.units.measure.AngularVelocity newTargetRateFeedforward)
      Modifies the TargetRateFeedforward parameter and returns itself.

      The rotational rate feedforward to add to the output of the heading controller, in radians per second. When using a motion profile for the target direction, this can be set to the current velocity reference of the profile.

      Parameters:
      newTargetRateFeedforward - Parameter to modify
      Returns:
      this object
    • withDeadband

      Modifies the Deadband parameter and returns itself.

      The allowable deadband of the request, in m/s.

      Parameters:
      newDeadband - Parameter to modify
      Returns:
      this object
    • withDeadband

      public SwerveRequest.FieldCentricFacingAngle withDeadband(edu.wpi.first.units.measure.LinearVelocity newDeadband)
      Modifies the Deadband parameter and returns itself.

      The allowable deadband of the request, in m/s.

      Parameters:
      newDeadband - Parameter to modify
      Returns:
      this object
    • withRotationalDeadband

      public SwerveRequest.FieldCentricFacingAngle withRotationalDeadband(double newRotationalDeadband)
      Modifies the RotationalDeadband parameter and returns itself.

      The rotational deadband of the request, in radians per second.

      Parameters:
      newRotationalDeadband - Parameter to modify
      Returns:
      this object
    • withRotationalDeadband

      public SwerveRequest.FieldCentricFacingAngle withRotationalDeadband(edu.wpi.first.units.measure.AngularVelocity newRotationalDeadband)
      Modifies the RotationalDeadband parameter and returns itself.

      The rotational deadband of the request, in radians per second.

      Parameters:
      newRotationalDeadband - Parameter to modify
      Returns:
      this object
    • withCenterOfRotation

      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.

      Parameters:
      newCenterOfRotation - Parameter to modify
      Returns:
      this object
    • withDriveRequestType

      Modifies the DriveRequestType parameter and returns itself.

      The type of control request to use for the drive motor.

      Parameters:
      newDriveRequestType - Parameter to modify
      Returns:
      this object
    • withSteerRequestType

      Modifies the SteerRequestType parameter and returns itself.

      The type of control request to use for the drive motor.

      Parameters:
      newSteerRequestType - Parameter to modify
      Returns:
      this object
    • withDesaturateWheelSpeeds

      public SwerveRequest.FieldCentricFacingAngle withDesaturateWheelSpeeds(boolean newDesaturateWheelSpeeds)
      Modifies the DesaturateWheelSpeeds parameter and returns itself.

      Whether to desaturate wheel speeds before applying. For more information, see the documentation of SwerveDriveKinematics.desaturateWheelSpeeds(edu.wpi.first.math.kinematics.SwerveModuleState[], double).

      Parameters:
      newDesaturateWheelSpeeds - Parameter to modify
      Returns:
      this object
    • withForwardPerspective

      Modifies the ForwardPerspective parameter and returns itself.

      The perspective to use when determining which direction is forward.

      Parameters:
      newForwardPerspective - Parameter to modify
      Returns:
      this object