Class SwerveRequest.FieldCentric

java.lang.Object
com.ctre.phoenix6.swerve.SwerveRequest.FieldCentric
All Implemented Interfaces:
SwerveRequest, SwerveRequest.NativeSwerveRequest
Enclosing interface:
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.

  • Field Details

  • Constructor Details

  • Method Details

    • withVelocityX

      public SwerveRequest.FieldCentric withVelocityX(double 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
    • withVelocityX

      public SwerveRequest.FieldCentric 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

      public SwerveRequest.FieldCentric withVelocityY(double 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
    • withVelocityY

      public SwerveRequest.FieldCentric 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
    • withRotationalRate

      public SwerveRequest.FieldCentric withRotationalRate(double newRotationalRate)
      Modifies the RotationalRate parameter and returns itself.

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

      public SwerveRequest.FieldCentric withRotationalRate(edu.wpi.first.units.measure.AngularVelocity newRotationalRate)
      Modifies the RotationalRate parameter and returns itself.

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

      public SwerveRequest.FieldCentric withDeadband(double 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
    • withDeadband

      public SwerveRequest.FieldCentric 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.FieldCentric 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.FieldCentric 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.FieldCentric 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
    • 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
    • applyNative

      public void applyNative(int id)
      Description copied from interface: SwerveRequest.NativeSwerveRequest
      Applies a native swerve request to the native drivetrain with the provided ID.

      When this is implemented, the regular SwerveRequest.apply(com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveControlParameters, com.ctre.phoenix6.swerve.SwerveModule...) function should do nothing (return OK). Additionally, this cannot be called from another swerve request's apply method, as this overrides the native swerve request of the drivetrain.

      Unlike SwerveRequest.apply(com.ctre.phoenix6.swerve.SwerveDrivetrain.SwerveControlParameters, com.ctre.phoenix6.swerve.SwerveModule...), this function is called every time SwerveDrivetrain.setControl(com.ctre.phoenix6.swerve.SwerveRequest) is run, not every loop of the odometry thread. Instead, the underlying native request is run at the full update frequency of the odometry thread.

      Specified by:
      applyNative in interface SwerveRequest.NativeSwerveRequest
      Parameters:
      id - ID of the native swerve drivetrain