Files
YAGSL/swervelib/SwerveInputStream.java

983 lines
33 KiB
Java
Raw Normal View History

2024-12-17 18:49:55 +00:00
package swervelib;
import edu.wpi.first.math.MathUtil;
2025-02-22 06:15:56 +00:00
import edu.wpi.first.math.controller.ProfiledPIDController;
2024-12-17 18:49:55 +00:00
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.DriverStation;
2025-01-06 15:44:15 +00:00
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.XboxController;
2024-12-17 18:49:55 +00:00
import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.DoubleSupplier;
import java.util.function.Supplier;
import swervelib.math.SwerveMath;
/**
2025-01-06 15:44:15 +00:00
* Helper class to easily transform Controller inputs into workable Chassis speeds. Intended to easily create an
* interface that generates {@link ChassisSpeeds} from {@link XboxController}
2024-12-17 18:49:55 +00:00
* <p>
2025-01-06 15:44:15 +00:00
* <br /> Inspired by SciBorgs FRC 1155. <br /> Example:
* <pre>
* {@code
* 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.
* }
* </pre>
2024-12-17 18:49:55 +00:00
*/
public class SwerveInputStream implements Supplier<ChassisSpeeds>
{
/**
* Translation suppliers.
*/
2025-02-22 06:15:56 +00:00
private final DoubleSupplier controllerTranslationX;
2024-12-17 18:49:55 +00:00
/**
* Translational supplier.
*/
2025-02-22 06:15:56 +00:00
private final DoubleSupplier controllerTranslationY;
2024-12-17 18:49:55 +00:00
/**
* {@link SwerveDrive} object for transformations.
*/
2025-02-22 06:15:56 +00:00
private final SwerveDrive swerveDrive;
2024-12-17 18:49:55 +00:00
/**
* Rotation supplier as angular velocity.
*/
2025-02-22 06:15:56 +00:00
private Optional<DoubleSupplier> controllerOmega = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Controller supplier as heading.
*/
2025-02-22 06:15:56 +00:00
private Optional<DoubleSupplier> controllerHeadingX = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Controller supplier as heading.
*/
2025-02-22 06:15:56 +00:00
private Optional<DoubleSupplier> controllerHeadingY = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Axis deadband for the controller.
*/
2025-02-22 06:15:56 +00:00
private Optional<Double> axisDeadband = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Translational axis scalar value, should be between (0, 1].
*/
2025-02-22 06:15:56 +00:00
private Optional<Double> translationAxisScale = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Angular velocity axis scalar value, should be between (0, 1]
*/
2025-02-22 06:15:56 +00:00
private Optional<Double> omegaAxisScale = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Target to aim at.
*/
2025-02-22 06:15:56 +00:00
private Optional<Pose2d> aimTarget = Optional.empty();
/**
* Target {@link Supplier<Pose2d>} to drive towards when driveToPose is enabled.
*/
private Optional<Supplier<Pose2d>> driveToPose = Optional.empty();
/**
* {@link ProfiledPIDController} for the X translation while driving to a pose. Units are m/s
*/
private Optional<ProfiledPIDController> driveToPoseXPIDController = Optional.empty();
/**
* {@link ProfiledPIDController} for the Y translation while driving to a pose. Units are m/s
*/
private Optional<ProfiledPIDController> driveToPoseYPIDController = Optional.empty();
/**
* {@link ProfiledPIDController} for the Rotational axis while driving to a pose. Units are m/s
*/
private Optional<ProfiledPIDController> driveToPoseOmegaPIDController = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Output {@link ChassisSpeeds} based on heading while this is True.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> headingEnabled = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Locked heading for {@link SwerveInputMode#TRANSLATION_ONLY}
*/
2025-02-22 06:15:56 +00:00
private Optional<Rotation2d> lockedHeading = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Output {@link ChassisSpeeds} based on aim while this is True.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> aimEnabled = Optional.empty();
/**
* Output {@link ChassisSpeeds} to move to a specific {@link Pose2d}.
*/
private Optional<BooleanSupplier> driveToPoseEnabled = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* Maintain current heading and drive without rotating, ideally.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> translationOnlyEnabled = Optional.empty();
2025-01-06 15:44:15 +00:00
/**
* Cube the translation magnitude from the controller.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> translationCube = Optional.empty();
2025-01-06 15:44:15 +00:00
/**
* Cube the angular velocity axis from the controller.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> omegaCube = Optional.empty();
2025-01-06 15:44:15 +00:00
/**
* Robot relative oriented output expected.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> robotRelative = Optional.empty();
2025-01-06 15:44:15 +00:00
/**
* Field oriented chassis output is relative to your current alliance.
*/
2025-02-22 06:15:56 +00:00
private Optional<BooleanSupplier> allianceRelative = Optional.empty();
/**
* Heading offset enable state.
*/
private Optional<BooleanSupplier> headingOffsetEnabled = Optional.empty();
/**
* Heading offset to apply during heading based control.
*/
private Optional<Rotation2d> headingOffset = Optional.empty();
2024-12-17 18:49:55 +00:00
/**
* {@link SwerveController} for simple control over heading.
*/
2025-02-22 06:15:56 +00:00
private SwerveController swerveController = null;
2024-12-17 18:49:55 +00:00
/**
* Current {@link SwerveInputMode} to use.
*/
2025-02-22 06:15:56 +00:00
private SwerveInputMode currentMode = SwerveInputMode.ANGULAR_VELOCITY;
2024-12-17 18:49:55 +00:00
/**
* Create a {@link SwerveInputStream} for an easy way to generate {@link ChassisSpeeds} from a driver controller.
*
* @param drive {@link SwerveDrive} object for transformation.
* @param x Translation X input in range of [-1, 1]
* @param y Translation Y input in range of [-1, 1]
*/
private SwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y)
{
controllerTranslationX = x;
controllerTranslationY = y;
swerveDrive = drive;
}
/**
* Create a {@link SwerveInputStream} for an easy way to generate {@link ChassisSpeeds} from a driver controller.
*
* @param drive {@link SwerveDrive} object for transformation.
* @param x Translation X input in range of [-1, 1]
* @param y Translation Y input in range of [-1, 1]
* @param rot Rotation input in range of [-1, 1]
*/
public SwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier rot)
{
this(drive, x, y);
controllerOmega = Optional.of(rot);
}
/**
* Create a {@link SwerveInputStream} for an easy way to generate {@link ChassisSpeeds} from a driver controller.
*
* @param drive {@link SwerveDrive} object for transformation.
* @param x Translation X input in range of [-1, 1]
* @param y Translation Y input in range of [-1, 1]
* @param headingX Heading X input in range of [-1, 1]
* @param headingY Heading Y input in range of [-1, 1]
*/
public SwerveInputStream(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y, DoubleSupplier headingX,
DoubleSupplier headingY)
{
this(drive, x, y);
controllerHeadingX = Optional.of(headingX);
controllerHeadingY = Optional.of(headingY);
}
/**
* Create basic {@link SwerveInputStream} without any rotation components.
*
* @param drive {@link SwerveDrive} object for transformation.
* @param x {@link DoubleSupplier} of the translation X axis of the controller joystick to use.
* @param y {@link DoubleSupplier} of the translation X axis of the controller joystick to use.
* @return {@link SwerveInputStream} to use as you see fit.
*/
public static SwerveInputStream of(SwerveDrive drive, DoubleSupplier x, DoubleSupplier y)
{
return new SwerveInputStream(drive, x, y);
}
2025-01-06 15:44:15 +00:00
/**
* Copy the {@link SwerveInputStream} object.
*
* @return Clone of current {@link SwerveInputStream}
*/
public SwerveInputStream copy()
{
SwerveInputStream newStream = new SwerveInputStream(swerveDrive, controllerTranslationX, controllerTranslationY);
newStream.controllerOmega = controllerOmega;
newStream.controllerHeadingX = controllerHeadingX;
newStream.controllerHeadingY = controllerHeadingY;
newStream.axisDeadband = axisDeadband;
newStream.translationAxisScale = translationAxisScale;
newStream.omegaAxisScale = omegaAxisScale;
2025-02-22 06:15:56 +00:00
newStream.driveToPose = driveToPose;
newStream.driveToPoseXPIDController = driveToPoseXPIDController;
newStream.driveToPoseYPIDController = driveToPoseYPIDController;
newStream.driveToPoseOmegaPIDController = driveToPoseOmegaPIDController;
2025-01-06 15:44:15 +00:00
newStream.aimTarget = aimTarget;
newStream.headingEnabled = headingEnabled;
newStream.aimEnabled = aimEnabled;
2025-02-22 06:15:56 +00:00
newStream.driveToPoseEnabled = driveToPoseEnabled;
2025-01-06 15:44:15 +00:00
newStream.currentMode = currentMode;
newStream.translationOnlyEnabled = translationOnlyEnabled;
newStream.lockedHeading = lockedHeading;
newStream.swerveController = swerveController;
newStream.omegaCube = omegaCube;
newStream.translationCube = translationCube;
newStream.robotRelative = robotRelative;
newStream.allianceRelative = allianceRelative;
2025-02-22 06:15:56 +00:00
newStream.headingOffsetEnabled = headingOffsetEnabled;
newStream.headingOffset = headingOffset;
2025-01-06 15:44:15 +00:00
return newStream;
}
/**
* Set the stream to output robot relative {@link ChassisSpeeds}
*
* @param enabled Robot-Relative {@link ChassisSpeeds} output.
* @return self
*/
public SwerveInputStream robotRelative(BooleanSupplier enabled)
{
robotRelative = Optional.of(enabled);
return this;
}
/**
* Set the stream to output robot relative {@link ChassisSpeeds}
*
* @param enabled Robot-Relative {@link ChassisSpeeds} output.
* @return self
*/
public SwerveInputStream robotRelative(boolean enabled)
{
robotRelative = enabled ? Optional.of(() -> enabled) : Optional.empty();
return this;
}
2025-02-22 06:15:56 +00:00
/**
* Drive to a given pose with the provided {@link ProfiledPIDController}s
*
* @param pose {@link Supplier<Pose2d>} for ease of use.
* @param xPIDController PID controller for the X axis, units are m/s.
* @param yPIDController PID controller for the Y axis, units are m/s.
* @param omegaPIDController PID Controller for rotational axis, units are rad/s.
* @return self
*/
public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDController xPIDController,
ProfiledPIDController yPIDController, ProfiledPIDController omegaPIDController)
{
driveToPose = Optional.of(pose);
driveToPoseXPIDController = Optional.of(xPIDController);
driveToPoseYPIDController = Optional.of(yPIDController);
driveToPoseOmegaPIDController = Optional.of(omegaPIDController);
return this;
}
/**
* Drive to a given pose with the provided {@link ProfiledPIDController}s
*
* @param pose {@link Supplier<Pose2d>} for ease of use.
* @param translation PID controller for the X and Y axis, units are m/s.
* @param rotation PID Controller for rotational axis, units are rad/s.
* @return self
*/
public SwerveInputStream driveToPose(Supplier<Pose2d> pose, ProfiledPIDController translation,
ProfiledPIDController rotation)
{
return driveToPose(pose, translation, new ProfiledPIDController(translation.getP(),
translation.getI(),
translation.getD(),
translation.getConstraints()), rotation);
}
/**
* Enable driving to the target pose.
*
* @param enabled Enable state of drive to pose.
* @return self.
*/
public SwerveInputStream driveToPoseEnabled(BooleanSupplier enabled)
{
driveToPoseEnabled = Optional.of(enabled);
return this;
}
/**
* Enable driving to the target pose.
*
* @param enabled Enable state of drive to pose.
* @return self.
*/
public SwerveInputStream driveToPoseEnabled(boolean enabled)
{
driveToPoseEnabled = enabled ? Optional.of(() -> enabled) : Optional.empty();
return this;
}
/**
* Heading offset enabled boolean supplier.
*
* @param enabled Enable state
* @return self
*/
public SwerveInputStream headingOffset(BooleanSupplier enabled)
{
headingOffsetEnabled = Optional.of(enabled);
return this;
}
/**
* Heading offset enable
*
* @param enabled Enable state
* @return self
*/
public SwerveInputStream headingOffset(boolean enabled)
{
headingOffsetEnabled = enabled ? Optional.of(() -> enabled) : Optional.empty();
return this;
}
/**
* Set the heading offset angle.
*
* @param angle {@link Rotation2d} offset to apply
* @return self
*/
public SwerveInputStream headingOffset(Rotation2d angle)
{
headingOffset = Optional.of(angle);
return this;
}
2025-01-06 15:44:15 +00:00
/**
* Modify the output {@link ChassisSpeeds} so that it is always relative to your alliance.
*
* @param enabled Alliance aware {@link ChassisSpeeds} output.
* @return self
*/
public SwerveInputStream allianceRelativeControl(BooleanSupplier enabled)
{
allianceRelative = Optional.of(enabled);
return this;
}
/**
* Modify the output {@link ChassisSpeeds} so that it is always relative to your alliance.
*
* @param enabled Alliance aware {@link ChassisSpeeds} output.
* @return self
*/
public SwerveInputStream allianceRelativeControl(boolean enabled)
{
allianceRelative = enabled ? Optional.of(() -> enabled) : Optional.empty();
return this;
}
/**
* Cube the angular velocity controller axis for a non-linear controls scheme.
*
* @param enabled Enabled state for the stream.
* @return self.
*/
public SwerveInputStream cubeRotationControllerAxis(BooleanSupplier enabled)
{
omegaCube = Optional.of(enabled);
return this;
}
/**
* Cube the angular velocity controller axis for a non-linear controls scheme.
*
* @param enabled Enabled state for the stream.
* @return self.
*/
public SwerveInputStream cubeRotationControllerAxis(boolean enabled)
{
omegaCube = Optional.of(() -> enabled);
return this;
}
/**
* Cube the translation axis magnitude for a non-linear control scheme.
*
* @param enabled Enabled state for the stream
* @return self
*/
public SwerveInputStream cubeTranslationControllerAxis(BooleanSupplier enabled)
{
translationOnlyEnabled = Optional.of(enabled);
return this;
}
/**
* Cube the translation axis magnitude for a non-linear control scheme
*
* @param enabled Enabled state for the stream
* @return self
*/
public SwerveInputStream cubeTranslationControllerAxis(boolean enabled)
{
translationCube = enabled ? Optional.of(() -> enabled) : Optional.empty();
return this;
}
2024-12-17 18:49:55 +00:00
/**
* Add a rotation axis for Angular Velocity control
*
* @param rot Rotation axis with values from [-1, 1]
* @return self
*/
public SwerveInputStream withControllerRotationAxis(DoubleSupplier rot)
{
controllerOmega = Optional.of(rot);
return this;
}
/**
* Add heading axis for Heading based control.
*
* @param headingX Heading X axis with values from [-1, 1]
* @param headingY Heading Y axis with values from [-1, 1]
* @return self
*/
public SwerveInputStream withControllerHeadingAxis(DoubleSupplier headingX, DoubleSupplier headingY)
{
controllerHeadingX = Optional.of(headingX);
controllerHeadingY = Optional.of(headingY);
return this;
}
/**
* Set a deadband for all controller axis.
*
* @param deadband Deadband to set, should be between [0, 1)
* @return self
*/
public SwerveInputStream deadband(double deadband)
{
axisDeadband = deadband == 0 ? Optional.empty() : Optional.of(deadband);
return this;
}
/**
* Scale the translation axis for {@link SwerveInputStream} by a constant scalar value.
*
* @param scaleTranslation Translation axis scalar value. (0, 1]
* @return this
*/
public SwerveInputStream scaleTranslation(double scaleTranslation)
{
translationAxisScale = scaleTranslation == 0 ? Optional.empty() : Optional.of(scaleTranslation);
return this;
}
/**
* Scale the rotation axis input for {@link SwerveInputStream} to reduce the range in which they operate.
*
* @param scaleRotation Angular velocity axis scalar value. (0, 1]
* @return this
*/
public SwerveInputStream scaleRotation(double scaleRotation)
{
omegaAxisScale = scaleRotation == 0 ? Optional.empty() : Optional.of(scaleRotation);
return this;
}
/**
* Output {@link ChassisSpeeds} based on heading while the supplier is True.
*
* @param trigger Supplier to use.
* @return this.
*/
public SwerveInputStream headingWhile(BooleanSupplier trigger)
{
headingEnabled = Optional.of(trigger);
return this;
}
/**
* Set the heading enable state.
*
* @param headingState Heading enabled state.
* @return this
*/
public SwerveInputStream headingWhile(boolean headingState)
{
if (headingState)
{
headingEnabled = Optional.of(() -> true);
} else
{
headingEnabled = Optional.empty();
}
return this;
}
/**
* Aim the {@link SwerveDrive} at this pose while driving.
*
* @param aimTarget {@link Pose2d} to point at.
* @return this
*/
public SwerveInputStream aim(Pose2d aimTarget)
{
this.aimTarget = aimTarget.equals(Pose2d.kZero) ? Optional.empty() : Optional.of(aimTarget);
return this;
}
/**
* Enable aiming while the trigger is true.
*
* @param trigger When True will enable aiming at the current target.
* @return this.
*/
public SwerveInputStream aimWhile(BooleanSupplier trigger)
{
aimEnabled = Optional.of(trigger);
return this;
}
/**
* Enable aiming while the trigger is true.
*
* @param trigger When True will enable aiming at the current target.
* @return this.
*/
public SwerveInputStream aimWhile(boolean trigger)
{
if (trigger)
{
aimEnabled = Optional.of(() -> true);
} else
{
aimEnabled = Optional.empty();
}
return this;
}
/**
* Enable locking of rotation and only translating, overrides everything.
*
* @param trigger Translation only while returns true.
* @return this
*/
public SwerveInputStream translationOnlyWhile(BooleanSupplier trigger)
{
translationOnlyEnabled = Optional.of(trigger);
return this;
}
/**
* Enable locking of rotation and only translating, overrides everything.
*
* @param translationState Translation only if true.
* @return this
*/
public SwerveInputStream translationOnlyWhile(boolean translationState)
{
if (translationState)
{
translationOnlyEnabled = Optional.of(() -> true);
} else
{
translationOnlyEnabled = Optional.empty();
}
return this;
}
/**
* Find {@link SwerveInputMode} based off existing parameters of the {@link SwerveInputStream}
*
* @return The calculated {@link SwerveInputMode}, defaults to {@link SwerveInputMode#ANGULAR_VELOCITY}.
*/
private SwerveInputMode findMode()
{
2025-02-22 06:15:56 +00:00
if (driveToPoseEnabled.isPresent() && driveToPoseEnabled.get().getAsBoolean())
{
if (driveToPose.isPresent())
{
if (driveToPoseOmegaPIDController.isPresent() && driveToPoseXPIDController.isPresent() &&
driveToPoseYPIDController.isPresent())
{
return SwerveInputMode.DRIVE_TO_POSE;
}
DriverStation.reportError("Drive to pose not supplied with pid controllers.", false);
}
DriverStation.reportError("Drive to pose enabled without supplier present.", false);
} else if (translationOnlyEnabled.isPresent() && translationOnlyEnabled.get().getAsBoolean())
2024-12-17 18:49:55 +00:00
{
return SwerveInputMode.TRANSLATION_ONLY;
} else if (aimEnabled.isPresent() && aimEnabled.get().getAsBoolean())
{
if (aimTarget.isPresent())
{
return SwerveInputMode.AIM;
} else
{
DriverStation.reportError(
"Attempting to enter AIM mode without target, please use SwerveInputStream.aim() to select a target first!",
false);
}
} else if (headingEnabled.isPresent() && headingEnabled.get().getAsBoolean())
{
if (controllerHeadingX.isPresent() && controllerHeadingY.isPresent())
{
return SwerveInputMode.HEADING;
} else
{
DriverStation.reportError(
"Attempting to enter HEADING mode without heading axis, please use SwerveInputStream.withControllerHeadingAxis to add heading axis!",
false);
}
} else if (controllerOmega.isEmpty())
{
DriverStation.reportError(
"Attempting to enter ANGULAR_VELOCITY mode without a rotation axis, please use SwerveInputStream.withControllerRotationAxis to add angular velocity axis!",
false);
return SwerveInputMode.TRANSLATION_ONLY;
}
return SwerveInputMode.ANGULAR_VELOCITY;
}
/**
* Transition smoothly from one mode to another.
*
* @param newMode New mode to transition too.
*/
private void transitionMode(SwerveInputMode newMode)
{
// Handle removing of current mode.
switch (currentMode)
{
case TRANSLATION_ONLY ->
{
lockedHeading = Optional.empty();
break;
}
2025-02-22 06:15:56 +00:00
case ANGULAR_VELOCITY, HEADING, AIM, DRIVE_TO_POSE ->
2024-12-17 18:49:55 +00:00
{
// Do nothing
break;
}
}
// Transitioning to new mode
switch (newMode)
{
case TRANSLATION_ONLY ->
{
lockedHeading = Optional.of(swerveDrive.getOdometryHeading());
break;
}
2025-02-22 06:15:56 +00:00
case ANGULAR_VELOCITY, DRIVE_TO_POSE ->
2024-12-17 18:49:55 +00:00
{
if (swerveDrive.headingCorrection)
{
swerveDrive.setHeadingCorrection(false);
}
break;
}
2025-02-22 06:15:56 +00:00
case HEADING, AIM ->
2024-12-17 18:49:55 +00:00
{
// Do nothing
break;
}
}
}
/**
* Apply the deadband if it exists.
*
* @param axisValue Axis value to apply the deadband too.
* @return axis value with deadband, else axis value straight.
*/
private double applyDeadband(double axisValue)
{
if (axisDeadband.isPresent())
{
return MathUtil.applyDeadband(axisValue, axisDeadband.get());
}
return axisValue;
}
/**
* Apply the scalar value if it exists.
*
* @param axisValue Axis value to apply teh scalar too.
* @return Axis value scaled by scalar value.
*/
private double applyRotationalScalar(double axisValue)
{
if (omegaAxisScale.isPresent())
{
return axisValue * omegaAxisScale.get();
}
return axisValue;
}
/**
* Scale the translational axis by the {@link SwerveInputStream#translationAxisScale} if it exists.
*
* @param xAxis X axis to scale.
* @param yAxis Y axis to scale.
* @return Scaled {@link Translation2d}
*/
private Translation2d applyTranslationScalar(double xAxis, double yAxis)
{
if (translationAxisScale.isPresent())
{
return SwerveMath.scaleTranslation(new Translation2d(xAxis, yAxis),
translationAxisScale.get());
}
return new Translation2d(xAxis, yAxis);
}
/**
2025-01-06 15:44:15 +00:00
* Apply the cube transformation on the given {@link Translation2d}
*
* @param translation {@link Translation2d} representing controller input
* @return Cubed {@link Translation2d} if the {@link SwerveInputStream#translationCube} is present.
*/
private Translation2d applyTranslationCube(Translation2d translation)
{
if (translationCube.isPresent() && translationCube.get().getAsBoolean())
{
return SwerveMath.cubeTranslation(translation);
}
return translation;
}
/**
* Apply the cube transformation on the given rotation controller axis
*
* @param rotationAxis Rotation controller axis to cube.
* @return Cubed axis value if the {@link SwerveInputStream#omegaCube} is present.
*/
private double applyOmegaCube(double rotationAxis)
{
if (omegaCube.isPresent() && omegaCube.get().getAsBoolean())
{
return Math.pow(rotationAxis, 3);
}
return rotationAxis;
}
/**
2025-02-22 06:15:56 +00:00
* Change {@link ChassisSpeeds} from robot relative if enabled.
2025-01-06 15:44:15 +00:00
*
2025-02-22 06:15:56 +00:00
* @param fieldRelativeSpeeds Field or robot relative speeds to translate into robot-relative speeds.
* @return Field relative {@link ChassisSpeeds}.
2025-01-06 15:44:15 +00:00
*/
private ChassisSpeeds applyRobotRelativeTranslation(ChassisSpeeds fieldRelativeSpeeds)
{
if (robotRelative.isPresent() && robotRelative.get().getAsBoolean())
{
2025-02-22 06:15:56 +00:00
return ChassisSpeeds.fromRobotRelativeSpeeds(fieldRelativeSpeeds, swerveDrive.getOdometryHeading());
2025-01-06 15:44:15 +00:00
}
return fieldRelativeSpeeds;
}
/**
* Apply alliance aware translation which flips the {@link Translation2d} if the robot is on the Blue alliance.
2024-12-17 18:49:55 +00:00
*
2025-01-06 15:44:15 +00:00
* @param fieldRelativeTranslation Field-relative {@link Translation2d} to flip.
* @return Alliance-oriented {@link Translation2d}
*/
private Translation2d applyAllianceAwareTranslation(Translation2d fieldRelativeTranslation)
{
if (allianceRelative.isPresent() && allianceRelative.get().getAsBoolean())
{
if (robotRelative.isPresent() && robotRelative.get().getAsBoolean())
{
throw new RuntimeException("Cannot use robot oriented control with Alliance aware movement!");
}
if (DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red)
{
return fieldRelativeTranslation.rotateBy(Rotation2d.k180deg);
}
}
return fieldRelativeTranslation;
}
/**
* Apply alliance aware translation which flips the {@link Rotation2d} if the robot is on the Blue alliance.
*
* @param fieldRelativeRotation Field-relative {@link Rotation2d} to flip.
* @return Alliance-oriented {@link Rotation2d}
*/
private Rotation2d applyAllianceAwareRotation(Rotation2d fieldRelativeRotation)
{
if (allianceRelative.isPresent() && allianceRelative.get().getAsBoolean())
{
if (robotRelative.isPresent() && robotRelative.get().getAsBoolean())
{
throw new RuntimeException("Cannot use robot oriented control with Alliance aware movement!");
}
if (DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == Alliance.Red)
{
return fieldRelativeRotation.rotateBy(Rotation2d.k180deg);
}
}
return fieldRelativeRotation;
}
2025-02-22 06:15:56 +00:00
/**
* Adds offset to rotation if one is set.
*
* @param fieldRelativeRotation Field-relative {@link Rotation2d} to offset
* @return Offsetted {@link Rotation2d}
*/
private Rotation2d applyHeadingOffset(Rotation2d fieldRelativeRotation)
{
if (headingOffsetEnabled.isPresent() && headingOffsetEnabled.get().getAsBoolean())
{
if (headingOffset.isPresent())
{
return fieldRelativeRotation.rotateBy(headingOffset.get());
}
}
return fieldRelativeRotation;
}
2025-01-06 15:44:15 +00:00
/**
* Gets a {@link ChassisSpeeds}
*
* @return {@link ChassisSpeeds}
2024-12-17 18:49:55 +00:00
*/
@Override
public ChassisSpeeds get()
{
double maximumChassisVelocity = swerveDrive.getMaximumChassisVelocity();
Translation2d scaledTranslation = applyTranslationScalar(applyDeadband(controllerTranslationX.getAsDouble()),
applyDeadband(controllerTranslationY.getAsDouble()));
2025-01-06 15:44:15 +00:00
scaledTranslation = applyTranslationCube(scaledTranslation);
scaledTranslation = applyAllianceAwareTranslation(scaledTranslation);
2024-12-17 18:49:55 +00:00
2025-01-06 15:44:15 +00:00
double vxMetersPerSecond = scaledTranslation.getX() * maximumChassisVelocity;
double vyMetersPerSecond = scaledTranslation.getY() * maximumChassisVelocity;
double omegaRadiansPerSecond = 0;
ChassisSpeeds speeds = new ChassisSpeeds();
2024-12-17 18:49:55 +00:00
SwerveInputMode newMode = findMode();
// Handle transitions here.
if (currentMode != newMode)
{
transitionMode(newMode);
}
if (swerveController == null)
{
swerveController = swerveDrive.getSwerveController();
}
switch (newMode)
{
case TRANSLATION_ONLY ->
{
omegaRadiansPerSecond = swerveController.headingCalculate(swerveDrive.getOdometryHeading().getRadians(),
lockedHeading.get().getRadians());
2025-01-06 15:44:15 +00:00
speeds = new ChassisSpeeds(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
2024-12-17 18:49:55 +00:00
break;
}
case ANGULAR_VELOCITY ->
{
2025-01-06 15:44:15 +00:00
omegaRadiansPerSecond = applyOmegaCube(applyRotationalScalar(applyDeadband(controllerOmega.get()
.getAsDouble()))) *
2024-12-17 18:49:55 +00:00
swerveDrive.getMaximumChassisAngularVelocity();
2025-01-06 15:44:15 +00:00
speeds = new ChassisSpeeds(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
2024-12-17 18:49:55 +00:00
break;
}
case HEADING ->
{
omegaRadiansPerSecond = swerveController.headingCalculate(swerveDrive.getOdometryHeading().getRadians(),
2025-02-22 06:15:56 +00:00
applyHeadingOffset(
applyAllianceAwareRotation(
Rotation2d.fromRadians(
swerveController.getJoystickAngle(
controllerHeadingX.get()
.getAsDouble(),
controllerHeadingY.get()
.getAsDouble())))).getRadians());
// Prevent rotation if controller heading inputs are not past axisDeadband
if (Math.abs(controllerHeadingX.get().getAsDouble()) + Math.abs(controllerHeadingY.get().getAsDouble()) <
axisDeadband.get())
{
omegaRadiansPerSecond = 0;
}
2025-01-06 15:44:15 +00:00
speeds = new ChassisSpeeds(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
2024-12-17 18:49:55 +00:00
break;
}
case AIM ->
{
Rotation2d currentHeading = swerveDrive.getOdometryHeading();
Translation2d relativeTrl = aimTarget.get().relativeTo(swerveDrive.getPose()).getTranslation();
Rotation2d target = new Rotation2d(relativeTrl.getX(), relativeTrl.getY()).plus(currentHeading);
omegaRadiansPerSecond = swerveController.headingCalculate(currentHeading.getRadians(), target.getRadians());
2025-01-06 15:44:15 +00:00
speeds = new ChassisSpeeds(vxMetersPerSecond, vyMetersPerSecond, omegaRadiansPerSecond);
2024-12-17 18:49:55 +00:00
break;
}
2025-02-22 06:15:56 +00:00
case DRIVE_TO_POSE ->
{
Pose2d target = driveToPose.get().get();
Pose2d pose = swerveDrive.getPose();
omegaRadiansPerSecond = driveToPoseOmegaPIDController.get().calculate(pose.getRotation()
.getRadians(),
target.getRotation().getRadians());
speeds = new ChassisSpeeds(driveToPoseXPIDController.get().calculate(pose.getX(), target.getX()),
driveToPoseYPIDController.get().calculate(pose.getY(), target.getY()),
omegaRadiansPerSecond);
}
2024-12-17 18:49:55 +00:00
}
currentMode = newMode;
2025-01-06 15:44:15 +00:00
return applyRobotRelativeTranslation(speeds);
}
/**
* Drive modes to keep track of.
*/
enum SwerveInputMode
{
/**
* Translation only mode, does not allow for rotation and maintains current heading.
*/
TRANSLATION_ONLY,
/**
* Output based off angular velocity
*/
ANGULAR_VELOCITY,
/**
* Output based off of heading.
*/
HEADING,
/**
* Output based off of targeting.
*/
2025-02-22 06:15:56 +00:00
AIM,
/**
* Drive to a target pose.
*/
DRIVE_TO_POSE
2024-12-17 18:49:55 +00:00
}
}