Skip to content

Commit

Permalink
Scale the input by 80% power
Browse files Browse the repository at this point in the history
Signed-off-by: thenetworkgrinch <thenetworkgrinch@users.noreply.github.com>
  • Loading branch information
thenetworkgrinch committed Jul 29, 2024
1 parent 075d5b6 commit 7451ce3
Showing 1 changed file with 4 additions and 4 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -252,8 +252,8 @@ public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translat
// swerveDrive.setHeadingCorrection(true); // Normally you would want heading correction for this kind of control.
return run(() -> {

Translation2d scaledInputs = SwerveMath.cubeTranslation(new Translation2d(translationX.getAsDouble(),
translationY.getAsDouble()));
Translation2d scaledInputs = SwerveMath.scaleTranslation(new Translation2d(translationX.getAsDouble(),
translationY.getAsDouble()), 0.8);

// Make the robot move
driveFieldOriented(swerveDrive.swerveController.getTargetSpeeds(scaledInputs.getX(), scaledInputs.getY(),
Expand Down Expand Up @@ -325,9 +325,9 @@ public Command driveCommand(DoubleSupplier translationX, DoubleSupplier translat
{
return run(() -> {
// Make the robot move
swerveDrive.drive(SwerveMath.cubeTranslation(new Translation2d(
swerveDrive.drive(SwerveMath.scaleTranslation(new Translation2d(
translationX.getAsDouble() * swerveDrive.getMaximumVelocity(),
translationY.getAsDouble() * swerveDrive.getMaximumVelocity())),
translationY.getAsDouble() * swerveDrive.getMaximumVelocity()), 0.8),
Math.pow(angularRotationX.getAsDouble(), 3) * swerveDrive.getMaximumAngularVelocity(),
true,
false);
Expand Down

0 comments on commit 7451ce3

Please sign in to comment.