diff --git a/src/main/java/frc/robot/swerve/SwerveSubsystem.java b/src/main/java/frc/robot/swerve/SwerveSubsystem.java index 1e9a473..22c5432 100644 --- a/src/main/java/frc/robot/swerve/SwerveSubsystem.java +++ b/src/main/java/frc/robot/swerve/SwerveSubsystem.java @@ -206,7 +206,7 @@ public void setChassisSpeeds(ChassisSpeeds speeds, boolean openLoop) { Logger.getInstance().recordOutput("Swerve/CommandedSpeeds/Omega", speeds.omegaRadiansPerSecond); // Twist computation. - double lookAheadSeconds = 0.1; + double lookAheadSeconds = 0.02; Pose2d target_pose = new Pose2d( lookAheadSeconds * speeds.vxMetersPerSecond,