diff --git a/src/main/java/frc/robot/commands/drive/DriveFieldOrientedHeadingSnapping.java b/src/main/java/frc/robot/commands/drive/DriveFieldOrientedHeadingSnapping.java index 24bb76ac..b3de7d91 100644 --- a/src/main/java/frc/robot/commands/drive/DriveFieldOrientedHeadingSnapping.java +++ b/src/main/java/frc/robot/commands/drive/DriveFieldOrientedHeadingSnapping.java @@ -58,7 +58,7 @@ public void execute() { RobotContainer.getScaledControllerLeftYAxis(), headingX, headingY); - + Translation2d translation = SwerveController.getTranslation2d(desiredSpeeds); drive.driveFieldOriented(translation, desiredSpeeds.omegaRadiansPerSecond); } diff --git a/src/main/java/frc/robot/commands/drive/DriveRobotOriented.java b/src/main/java/frc/robot/commands/drive/DriveRobotOriented.java index 74c6a1c8..6abcd3cc 100644 --- a/src/main/java/frc/robot/commands/drive/DriveRobotOriented.java +++ b/src/main/java/frc/robot/commands/drive/DriveRobotOriented.java @@ -34,7 +34,7 @@ public void initialize() {} // Called every time the scheduler runs while the command is scheduled. @Override public void execute() { - double x = RobotContainer.getScaledControllerLeftYAxis() * Constants.Drive.MAX_SPEED; + double x = RobotContainer.getScaledControllerLeftYAxis() * Constants.Drive.MAX_SPEED; double y = RobotContainer.getScaledControllerLeftXAxis() * Constants.Drive.MAX_SPEED; double z = RobotContainer.getScaledControllerRightXAxis() * Constants.Drive.MAX_ANGULAR_SPEED; Translation2d translation = new Translation2d(x, y);