Package swervelib
Class SwerveInputStream
java.lang.Object
swervelib.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 aSwerveInputStream
for an easy way to generateChassisSpeeds
from a driver controller.SwerveInputStream
(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier headingX, DoubleSupplier headingY) Create aSwerveInputStream
for an easy way to generateChassisSpeeds
from a driver controller. -
Method Summary
Modifier and TypeMethodDescriptionAim theSwerveDrive
at this pose while driving.aimWhile
(boolean trigger) Enable aiming while the trigger is true.aimWhile
(BooleanSupplier trigger) Enable aiming while the trigger is true.allianceRelativeControl
(boolean enabled) Modify the outputChassisSpeeds
so that it is always relative to your alliance.allianceRelativeControl
(BooleanSupplier enabled) Modify the outputChassisSpeeds
so that it is always relative to your alliance.copy()
Copy theSwerveInputStream
object.cubeRotationControllerAxis
(boolean enabled) Cube the angular velocity controller axis for a non-linear controls scheme.Cube the angular velocity controller axis for a non-linear controls scheme.cubeTranslationControllerAxis
(boolean enabled) Cube the translation axis magnitude for a non-linear control schemeCube the translation axis magnitude for a non-linear control scheme.deadband
(double deadband) Set a deadband for all controller axis.get()
Gets aChassisSpeeds
headingOffset
(boolean enabled) Heading offset enableheadingOffset
(Rotation2d angle) Set the heading offset angle.headingOffset
(BooleanSupplier enabled) Heading offset enabled boolean supplier.headingWhile
(boolean headingState) Set the heading enable state.headingWhile
(BooleanSupplier trigger) OutputChassisSpeeds
based on heading while the supplier is True.static SwerveInputStream
of
(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y) Create basicSwerveInputStream
without any rotation components.robotRelative
(boolean enabled) Set the stream to output robot relativeChassisSpeeds
robotRelative
(BooleanSupplier enabled) Set the stream to output robot relativeChassisSpeeds
scaleRotation
(double scaleRotation) Scale the rotation axis input forSwerveInputStream
to reduce the range in which they operate.scaleTranslation
(double scaleTranslation) Scale the translation axis forSwerveInputStream
by a constant scalar value.translationOnlyWhile
(boolean translationState) Enable locking of rotation and only translating, overrides everything.translationOnlyWhile
(BooleanSupplier trigger) Enable locking of rotation and only translating, overrides everything.withControllerHeadingAxis
(DoubleSupplier headingX, DoubleSupplier headingY) Add heading axis for Heading based control.Add a rotation axis for Angular Velocity control
-
Constructor Details
-
SwerveInputStream
Create aSwerveInputStream
for an easy way to generateChassisSpeeds
from a driver controller.- Parameters:
drive
-SwerveDrive
object 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 aSwerveInputStream
for an easy way to generateChassisSpeeds
from a driver controller.- Parameters:
drive
-SwerveDrive
object 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 basicSwerveInputStream
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
Copy theSwerveInputStream
object.- Returns:
- Clone of current
SwerveInputStream
-
robotRelative
Set the stream to output robot relativeChassisSpeeds
- Parameters:
enabled
- Robot-RelativeChassisSpeeds
output.- Returns:
- self
-
robotRelative
Set the stream to output robot relativeChassisSpeeds
- Parameters:
enabled
- Robot-RelativeChassisSpeeds
output.- Returns:
- self
-
headingOffset
Heading offset enabled boolean supplier.- Parameters:
enabled
- Enable state- Returns:
- self
-
headingOffset
Heading offset enable- Parameters:
enabled
- Enable state- Returns:
- self
-
headingOffset
Set the heading offset angle.- Parameters:
angle
-Rotation2d
offset to apply- Returns:
- self
-
allianceRelativeControl
Modify the outputChassisSpeeds
so that it is always relative to your alliance.- Parameters:
enabled
- Alliance awareChassisSpeeds
output.- Returns:
- self
-
allianceRelativeControl
Modify the outputChassisSpeeds
so that it is always relative to your alliance.- Parameters:
enabled
- Alliance awareChassisSpeeds
output.- Returns:
- self
-
cubeRotationControllerAxis
Cube the angular velocity controller axis for a non-linear controls scheme.- Parameters:
enabled
- Enabled state for the stream.- Returns:
- self.
-
cubeRotationControllerAxis
Cube the angular velocity controller axis for a non-linear controls scheme.- Parameters:
enabled
- Enabled state for the stream.- Returns:
- self.
-
cubeTranslationControllerAxis
Cube the translation axis magnitude for a non-linear control scheme.- Parameters:
enabled
- Enabled state for the stream- Returns:
- self
-
cubeTranslationControllerAxis
Cube the translation axis magnitude for a non-linear control scheme- Parameters:
enabled
- Enabled state for the stream- 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
-
scaleTranslation
Scale the translation axis forSwerveInputStream
by a constant scalar value.- Parameters:
scaleTranslation
- Translation axis scalar value. (0, 1]- Returns:
- this
-
scaleRotation
Scale the rotation axis input forSwerveInputStream
to reduce the range in which they operate.- Parameters:
scaleRotation
- Angular velocity axis scalar value. (0, 1]- Returns:
- this
-
headingWhile
OutputChassisSpeeds
based on heading while the supplier is True.- Parameters:
trigger
- Supplier to use.- Returns:
- this.
-
headingWhile
Set the heading enable state.- Parameters:
headingState
- Heading enabled state.- Returns:
- this
-
aim
Aim theSwerveDrive
at this pose while driving.- Parameters:
aimTarget
-Pose2d
to point at.- Returns:
- this
-
aimWhile
Enable aiming while the trigger is true.- Parameters:
trigger
- When True will enable aiming at the current target.- Returns:
- this.
-
aimWhile
Enable aiming while the trigger is true.- Parameters:
trigger
- When True will enable aiming at the current target.- Returns:
- this.
-
translationOnlyWhile
Enable locking of rotation and only translating, overrides everything.- Parameters:
trigger
- Translation only while returns true.- Returns:
- this
-
translationOnlyWhile
Enable locking of rotation and only translating, overrides everything.- Parameters:
translationState
- Translation only if true.- Returns:
- this
-
get
Gets aChassisSpeeds
- Specified by:
get
in interfaceSupplier<ChassisSpeeds>
- Returns:
ChassisSpeeds
-