Class SwerveRequest.ApplyFieldSpeeds

java.lang.Object
com.ctre.phoenix6.swerve.SwerveRequest.ApplyFieldSpeeds
All Implemented Interfaces:
SwerveRequest, SwerveRequest.NativeSwerveRequest
Enclosing interface:
SwerveRequest

Accepts a generic field-centric ChassisSpeeds to apply to the drivetrain.
  • Field Details

  • Constructor Details

  • Method Details

    • withSpeeds

      Modifies the Speeds parameter and returns itself.

      The field-centric chassis speeds to apply to the drivetrain.

      Parameters:
      newSpeeds - Parameter to modify
      Returns:
      this object
    • withWheelForceFeedforwardsX

      public SwerveRequest.ApplyFieldSpeeds withWheelForceFeedforwardsX(double[] newWheelForceFeedforwardsX)
      Modifies the WheelForceFeedforwardsX parameter and returns itself.

      Field-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

      These forces should include friction applied to the ground.

      The order of the forces should match the order of the modules returned from SwerveDrivetrain.

      Parameters:
      newWheelForceFeedforwardsX - Parameter to modify
      Returns:
      this object
    • withWheelForceFeedforwardsX

      public SwerveRequest.ApplyFieldSpeeds withWheelForceFeedforwardsX(edu.wpi.first.units.measure.Force[] newWheelForceFeedforwardsX)
      Modifies the WheelForceFeedforwardsX parameter and returns itself.

      Field-centric wheel force feedforwards to apply in the X direction, in newtons. X is defined as forward according to WPILib convention, so this determines the forward forces to apply.

      These forces should include friction applied to the ground.

      The order of the forces should match the order of the modules returned from SwerveDrivetrain.

      Parameters:
      newWheelForceFeedforwardsX - Parameter to modify
      Returns:
      this object
    • withWheelForceFeedforwardsY

      public SwerveRequest.ApplyFieldSpeeds withWheelForceFeedforwardsY(double[] newWheelForceFeedforwardsY)
      Modifies the WheelForceFeedforwardsY parameter and returns itself.

      Field-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

      These forces should include friction applied to the ground.

      The order of the forces should match the order of the modules returned from SwerveDrivetrain.

      Parameters:
      newWheelForceFeedforwardsY - Parameter to modify
      Returns:
      this object
    • withWheelForceFeedforwardsY

      public SwerveRequest.ApplyFieldSpeeds withWheelForceFeedforwardsY(edu.wpi.first.units.measure.Force[] newWheelForceFeedforwardsY)
      Modifies the WheelForceFeedforwardsY parameter and returns itself.

      Field-centric wheel force feedforwards to apply in the Y direction, in newtons. Y is defined as to the left according to WPILib convention, so this determines the forces to apply to the left.

      These forces should include friction applied to the ground.

      The order of the forces should match the order of the modules returned from SwerveDrivetrain.

      Parameters:
      newWheelForceFeedforwardsY - 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.ApplyFieldSpeeds 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