Package swervelib

Class SwerveInputStream

java.lang.Object
swervelib.SwerveInputStream
All Implemented Interfaces:
Supplier<ChassisSpeeds>

public class SwerveInputStream extends Object implements Supplier<ChassisSpeeds>
Helper class to easily transform Controller inputs into workable Chassis speeds. Intended to easily create an interface that generates ChassisSpeeds from XboxController


Inspired by SciBorgs FRC 1155.
Example:


 XboxController driverXbox = new XboxController(0);

 SwerveInputStream driveAngularVelocity = SwerveInputStream.of(drivebase.getSwerveDrive(),
                                                               () -> driverXbox.getLeftY() * -1,
                                                               () -> driverXbox.getLeftX() * -1) // Axis which give the desired translational angle and speed.
                                                           .withControllerRotationAxis(driverXbox::getRightX) // Axis which give the desired angular velocity.
                                                           .deadband(0.01)                  // Controller deadband
                                                           .scaleTranslation(0.8)           // Scaled controller translation axis
                                                           .allianceRelativeControl(true);  // Alliance relative controls.

 SwerveInputStream driveDirectAngle = driveAngularVelocity.copy()  // Copy the stream so further changes do not affect driveAngularVelocity
                                                          .withControllerHeadingAxis(driverXbox::getRightX,
                                                                                     driverXbox::getRightY) // Axis which give the desired heading angle using trigonometry.
                                                          .headingWhile(true); // Enable heading based control.
 
  • Constructor Details

  • Method Details

    • of

      public static SwerveInputStream of(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y)
      Create basic SwerveInputStream without any rotation components.
      Parameters:
      drive - SwerveDrive object for transformation.
      x - DoubleSupplier of the translation X axis of the controller joystick to use.
      y - DoubleSupplier of the translation X axis of the controller joystick to use.
      Returns:
      SwerveInputStream to use as you see fit.
    • copy

      public SwerveInputStream copy()
      Copy the SwerveInputStream object.
      Returns:
      Clone of current SwerveInputStream
    • robotRelative

      public SwerveInputStream robotRelative(BooleanSupplier enabled)
      Set the stream to output robot relative ChassisSpeeds
      Parameters:
      enabled - Robot-Relative ChassisSpeeds output.
      Returns:
      self
    • robotRelative

      public SwerveInputStream robotRelative(boolean enabled)
      Set the stream to output robot relative ChassisSpeeds
      Parameters:
      enabled - Robot-Relative ChassisSpeeds output.
      Returns:
      self
    • headingOffset

      public SwerveInputStream headingOffset(BooleanSupplier enabled)
      Heading offset enabled boolean supplier.
      Parameters:
      enabled - Enable state
      Returns:
      self
    • headingOffset

      public SwerveInputStream headingOffset(boolean enabled)
      Heading offset enable
      Parameters:
      enabled - Enable state
      Returns:
      self
    • headingOffset

      public SwerveInputStream headingOffset(Rotation2d angle)
      Set the heading offset angle.
      Parameters:
      angle - Rotation2d offset to apply
      Returns:
      self
    • allianceRelativeControl

      public SwerveInputStream allianceRelativeControl(BooleanSupplier enabled)
      Modify the output ChassisSpeeds so that it is always relative to your alliance.
      Parameters:
      enabled - Alliance aware ChassisSpeeds output.
      Returns:
      self
    • allianceRelativeControl

      public SwerveInputStream allianceRelativeControl(boolean enabled)
      Modify the output ChassisSpeeds so that it is always relative to your alliance.
      Parameters:
      enabled - Alliance aware ChassisSpeeds output.
      Returns:
      self
    • cubeRotationControllerAxis

      public SwerveInputStream cubeRotationControllerAxis(BooleanSupplier enabled)
      Cube the angular velocity controller axis for a non-linear controls scheme.
      Parameters:
      enabled - Enabled state for the stream.
      Returns:
      self.
    • cubeRotationControllerAxis

      public SwerveInputStream cubeRotationControllerAxis(boolean enabled)
      Cube the angular velocity controller axis for a non-linear controls scheme.
      Parameters:
      enabled - Enabled state for the stream.
      Returns:
      self.
    • cubeTranslationControllerAxis

      public SwerveInputStream cubeTranslationControllerAxis(BooleanSupplier enabled)
      Cube the translation axis magnitude for a non-linear control scheme.
      Parameters:
      enabled - Enabled state for the stream
      Returns:
      self
    • cubeTranslationControllerAxis

      public SwerveInputStream cubeTranslationControllerAxis(boolean enabled)
      Cube the translation axis magnitude for a non-linear control scheme
      Parameters:
      enabled - Enabled state for the stream
      Returns:
      self
    • withControllerRotationAxis

      public SwerveInputStream withControllerRotationAxis(DoubleSupplier rot)
      Add a rotation axis for Angular Velocity control
      Parameters:
      rot - Rotation axis with values from [-1, 1]
      Returns:
      self
    • withControllerHeadingAxis

      public SwerveInputStream withControllerHeadingAxis(DoubleSupplier headingX, DoubleSupplier headingY)
      Add heading axis for Heading based control.
      Parameters:
      headingX - Heading X axis with values from [-1, 1]
      headingY - Heading Y axis with values from [-1, 1]
      Returns:
      self
    • deadband

      public SwerveInputStream deadband(double deadband)
      Set a deadband for all controller axis.
      Parameters:
      deadband - Deadband to set, should be between [0, 1)
      Returns:
      self
    • scaleTranslation

      public SwerveInputStream scaleTranslation(double scaleTranslation)
      Scale the translation axis for SwerveInputStream by a constant scalar value.
      Parameters:
      scaleTranslation - Translation axis scalar value. (0, 1]
      Returns:
      this
    • scaleRotation

      public SwerveInputStream scaleRotation(double scaleRotation)
      Scale the rotation axis input for SwerveInputStream to reduce the range in which they operate.
      Parameters:
      scaleRotation - Angular velocity axis scalar value. (0, 1]
      Returns:
      this
    • headingWhile

      public SwerveInputStream headingWhile(BooleanSupplier trigger)
      Output ChassisSpeeds based on heading while the supplier is True.
      Parameters:
      trigger - Supplier to use.
      Returns:
      this.
    • headingWhile

      public SwerveInputStream headingWhile(boolean headingState)
      Set the heading enable state.
      Parameters:
      headingState - Heading enabled state.
      Returns:
      this
    • aim

      public SwerveInputStream aim(Pose2d aimTarget)
      Aim the SwerveDrive at this pose while driving.
      Parameters:
      aimTarget - Pose2d to point at.
      Returns:
      this
    • aimWhile

      public SwerveInputStream aimWhile(BooleanSupplier trigger)
      Enable aiming while the trigger is true.
      Parameters:
      trigger - When True will enable aiming at the current target.
      Returns:
      this.
    • aimWhile

      public SwerveInputStream aimWhile(boolean trigger)
      Enable aiming while the trigger is true.
      Parameters:
      trigger - When True will enable aiming at the current target.
      Returns:
      this.
    • translationOnlyWhile

      public SwerveInputStream translationOnlyWhile(BooleanSupplier trigger)
      Enable locking of rotation and only translating, overrides everything.
      Parameters:
      trigger - Translation only while returns true.
      Returns:
      this
    • translationOnlyWhile

      public SwerveInputStream translationOnlyWhile(boolean translationState)
      Enable locking of rotation and only translating, overrides everything.
      Parameters:
      translationState - Translation only if true.
      Returns:
      this
    • get

      public ChassisSpeeds get()
      Specified by:
      get in interface Supplier<ChassisSpeeds>
      Returns:
      ChassisSpeeds