Class SwerveInputStream

java.lang.Object
yams.mechanisms.swerve.utility.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.
    • clone

      public SwerveInputStream clone()
      Copy the SwerveInputStream object.
      Overrides:
      clone in class Object
      Returns:
      Clone of current SwerveInputStream
    • withMaximumLinearVelocity

      public SwerveInputStream withMaximumLinearVelocity(LinearVelocity velocity)
      Maximum linear velocity to use for the SwerveDrive object, will be translated to Meters per Second. Default is 4 Meters per Second.
      Parameters:
      velocity - Linear velocity to use.
      Returns:
      SwerveInputStream to use as you see fit.
    • withMaximumAngularVelocity

      public SwerveInputStream withMaximumAngularVelocity(AngularVelocity velocity)
      Maximum angular velocity to use for the SwerveDrive object, will be translated to Rotations per Second. Default is 1 Rotation per Second.
      Parameters:
      velocity - Angular velocity to use.
      Returns:
      SwerveInputStream to use as you see fit.
    • withRobotRelative

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

      public SwerveInputStream withRobotRelative()
      Set the stream to output robot relative ChassisSpeeds
      Returns:
      self
    • driveToPose

      @Deprecated(since="2025.10.31", forRemoval=true) public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDController xPIDController, ProfiledPIDController omegaPIDController)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Drive to a given pose with the provided ProfiledPIDControllers
      Parameters:
      pose - Supplier<Pose2d> for ease of use.
      xPIDController - PID controller for the translational axis, units are m/s.
      omegaPIDController - PID Controller for rotational axis, units are rad/s.
      Returns:
      self
    • driveToPoseEnabled

      @Deprecated(since="2025.10.31", forRemoval=true) public SwerveInputStream driveToPoseEnabled(BooleanSupplier enabled)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Enable driving to the target pose.
      Parameters:
      enabled - Enable state of drive to pose.
      Returns:
      self.
    • driveToPoseEnabled

      @Deprecated(since="2025.10.31", forRemoval=true) public SwerveInputStream driveToPoseEnabled(boolean enabled)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Enable driving to the target pose.
      Parameters:
      enabled - Enable state of drive to pose.
      Returns:
      self.
    • withTranslationHeadingOffset

      public SwerveInputStream withTranslationHeadingOffset(Rotation2d angle, BooleanSupplier enabled)
      Heading offset enabled boolean supplier.
      Parameters:
      angle - Rotation2d offset to apply
      enabled - Enable state
      Returns:
      self
    • withTranslationHeadingOffset

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

      public SwerveInputStream withAllianceRelativeControl()
      Modify the output ChassisSpeeds so that it is always relative to your alliance.
      Returns:
      self
    • withAllianceRelativeControl

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

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

      public SwerveInputStream withCubeRotationControllerAxis()
      Cube the angular velocity controller axis for a non-linear controls scheme.
      Returns:
      self.
    • withCubeTranslationControllerAxis

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

      public SwerveInputStream withCubeTranslationControllerAxis()
      Cube the translation axis magnitude for a non-linear control scheme
      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
    • withDeadband

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

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

      public SwerveInputStream withScaleRotation(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
    • withHeadingControl

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

      public SwerveInputStream withAim(Pose2d aimTarget, BooleanSupplier trigger)
      Aim the SwerveDrive at this pose while driving.
      Parameters:
      trigger - When True will enable aiming at the current target.
      aimTarget - Pose2d to point at.
      Returns:
      this
    • withTranslationOnly

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

      @Deprecated(since="2025.10.31", forRemoval=true) public void resetDriveToPosePIDControllers()
      Deprecated, for removal: This API element is subject to removal in a future version.
      Reset the drive to pose PID controllers when switching targets.
    • atTargetPose

      public boolean atTargetPose(double toleranceMeters)
      When the SwerveInputStream is in SwerveInputStream.SwerveInputMode.DRIVE_TO_POSE this function will return if the robot is at the desired pose within the defined tolerance.
      Parameters:
      toleranceMeters - Tolerance in meters.
      Returns:
      At target pose, true if current mode is not SwerveInputStream.SwerveInputMode.DRIVE_TO_POSE and no pose supplier has been given.
    • get

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