Package yams.mechanisms.swerve.utility
Class SwerveInputStream
java.lang.Object
yams.mechanisms.swerve.utility.SwerveInputStream
- All Implemented Interfaces:
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 Summary
ConstructorsConstructorDescriptionSwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier rot) Create aSwerveInputStreamfor an easy way to generateChassisSpeedsfrom a driver controller.SwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier headingX, DoubleSupplier headingY) Create aSwerveInputStreamfor an easy way to generateChassisSpeedsfrom a driver controller. -
Method Summary
Modifier and TypeMethodDescriptionbooleanatTargetPose(double toleranceMeters) When theSwerveInputStreamis inSwerveInputStream.SwerveInputMode.DRIVE_TO_POSEthis function will return if the robot is at the desired pose within the defined tolerance.clone()Copy theSwerveInputStreamobject.deadband(double deadband) Set a deadband for all controller axis.driveToPose(Supplier<Pose2d> pose, ProfiledPIDController xPIDController, ProfiledPIDController omegaPIDController) Deprecated, for removal: This API element is subject to removal in a future version.driveToPoseEnabled(boolean enabled) Deprecated, for removal: This API element is subject to removal in a future version.driveToPoseEnabled(BooleanSupplier enabled) Deprecated, for removal: This API element is subject to removal in a future version.get()Gets aChassisSpeedsstatic SwerveInputStreamof(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y) Create basicSwerveInputStreamwithout any rotation components.voidDeprecated, for removal: This API element is subject to removal in a future version.withAim(Pose2d aimTarget, BooleanSupplier trigger) Aim theSwerveDriveat this pose while driving.Modify the outputChassisSpeedsso that it is always relative to your alliance.Modify the outputChassisSpeedsso that it is always relative to your alliance.withControllerHeadingAxis(DoubleSupplier headingX, DoubleSupplier headingY) Add heading axis for Heading based control.Add a rotation axis for Angular Velocity controlCube the angular velocity controller axis for a non-linear controls scheme.Cube the angular velocity controller axis for a non-linear controls scheme.Cube the translation axis magnitude for a non-linear control schemeCube the translation axis magnitude for a non-linear control scheme.withDeadband(double deadband) Set a deadband for all controller axis.withHeadingControl(BooleanSupplier trigger) OutputChassisSpeedsbased on heading while the supplier is True.withMaximumAngularVelocity(AngularVelocity velocity) Maximum angular velocity to use for theSwerveDriveobject, will be translated to Rotations per Second.withMaximumLinearVelocity(LinearVelocity velocity) Maximum linear velocity to use for theSwerveDriveobject, will be translated to Meters per Second.Set the stream to output robot relativeChassisSpeedswithRobotRelative(BooleanSupplier enabled) Set the stream to output robot relativeChassisSpeedswithScaleRotation(double scaleRotation) Scale the rotation axis input forSwerveInputStreamto reduce the range in which they operate.withScaleTranslation(double scaleTranslation) Scale the translation axis forSwerveInputStreamby a constant scalar value.Set the heading offset angle.withTranslationHeadingOffset(Rotation2d angle, BooleanSupplier enabled) Heading offset enabled boolean supplier.withTranslationOnly(BooleanSupplier trigger) Enable locking of rotation and only translating, overrides everything.
-
Constructor Details
-
SwerveInputStream
Create aSwerveInputStreamfor an easy way to generateChassisSpeedsfrom a driver controller.- Parameters:
drive-SwerveDriveobject for transformation.x- Translation X input in range of [-1, 1]y- Translation Y input in range of [-1, 1]rot- Rotation input in range of [-1, 1]
-
SwerveInputStream
public SwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier headingX, DoubleSupplier headingY) Create aSwerveInputStreamfor an easy way to generateChassisSpeedsfrom a driver controller.- Parameters:
drive-SwerveDriveobject for transformation.x- Translation X input in range of [-1, 1]y- Translation Y input in range of [-1, 1]headingX- Heading X input in range of [-1, 1]headingY- Heading Y input in range of [-1, 1]
-
-
Method Details
-
of
Create basicSwerveInputStreamwithout any rotation components.- Parameters:
drive-SwerveDriveobject for transformation.x-DoubleSupplierof the translation X axis of the controller joystick to use.y-DoubleSupplierof the translation X axis of the controller joystick to use.- Returns:
SwerveInputStreamto use as you see fit.
-
clone
Copy theSwerveInputStreamobject.- Overrides:
clonein classObject- Returns:
- Clone of current
SwerveInputStream
-
withMaximumLinearVelocity
Maximum linear velocity to use for theSwerveDriveobject, will be translated to Meters per Second. Default is 4 Meters per Second.- Parameters:
velocity- Linear velocity to use.- Returns:
SwerveInputStreamto use as you see fit.
-
withMaximumAngularVelocity
Maximum angular velocity to use for theSwerveDriveobject, will be translated to Rotations per Second. Default is 1 Rotation per Second.- Parameters:
velocity- Angular velocity to use.- Returns:
SwerveInputStreamto use as you see fit.
-
withRobotRelative
Set the stream to output robot relativeChassisSpeeds- Parameters:
enabled- Robot-RelativeChassisSpeedsoutput.- Returns:
- self
-
withRobotRelative
Set the stream to output robot relativeChassisSpeeds- 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 providedProfiledPIDControllers -
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
Heading offset enabled boolean supplier.- Parameters:
angle-Rotation2doffset to applyenabled- Enable state- Returns:
- self
-
withTranslationHeadingOffset
Set the heading offset angle.- Parameters:
angle-Rotation2doffset to apply- Returns:
- self
-
withAllianceRelativeControl
Modify the outputChassisSpeedsso that it is always relative to your alliance.- Returns:
- self
-
withAllianceRelativeControl
Modify the outputChassisSpeedsso that it is always relative to your alliance.- Parameters:
enabled- Alliance awareChassisSpeedsoutput.- Returns:
- self
-
withCubeRotationControllerAxis
Cube the angular velocity controller axis for a non-linear controls scheme.- Parameters:
enabled- Enabled state for the stream.- Returns:
- self.
-
withCubeRotationControllerAxis
Cube the angular velocity controller axis for a non-linear controls scheme.- Returns:
- self.
-
withCubeTranslationControllerAxis
Cube the translation axis magnitude for a non-linear control scheme.- Parameters:
enabled- Enabled state for the stream- Returns:
- self
-
withCubeTranslationControllerAxis
Cube the translation axis magnitude for a non-linear control scheme- Returns:
- self
-
withControllerRotationAxis
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
Set a deadband for all controller axis.- Parameters:
deadband- Deadband to set, should be between [0, 1)- Returns:
- self
-
withDeadband
Set a deadband for all controller axis.- Parameters:
deadband- Deadband to set, should be between [0, 1)- Returns:
- self
-
withScaleTranslation
Scale the translation axis forSwerveInputStreamby a constant scalar value.- Parameters:
scaleTranslation- Translation axis scalar value. (0, 1]- Returns:
- this
-
withScaleRotation
Scale the rotation axis input forSwerveInputStreamto reduce the range in which they operate.- Parameters:
scaleRotation- Angular velocity axis scalar value. (0, 1]- Returns:
- this
-
withHeadingControl
OutputChassisSpeedsbased on heading while the supplier is True.- Parameters:
trigger- Supplier to use.- Returns:
- this.
-
withAim
Aim theSwerveDriveat this pose while driving.- Parameters:
trigger- When True will enable aiming at the current target.aimTarget-Pose2dto point at.- Returns:
- this
-
withTranslationOnly
Enable locking of rotation and only translating, overrides everything.- Parameters:
trigger- Translation only while returns true.- Returns:
- this
-
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 theSwerveInputStreamis inSwerveInputStream.SwerveInputMode.DRIVE_TO_POSEthis 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_POSEand no pose supplier has been given.
-
get
Gets aChassisSpeeds- Specified by:
getin interfaceSupplier<ChassisSpeeds>- Returns:
ChassisSpeeds
-