diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java index f08eca3..3045a34 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/ForwardVelocityTuner.java @@ -143,6 +143,13 @@ public class ForwardVelocityTuner extends OpMode { velocities.remove(0); } } else { + leftFront.setPower(0); + leftRear.setPower(0); + rightFront.setPower(0); + rightRear.setPower(0); + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + } double average = 0; for (Double velocity : velocities) { average += velocity; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java index 36da360..a15010a 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/pedroPathing/tuning/StrafeVelocityTuner.java @@ -141,6 +141,13 @@ public class StrafeVelocityTuner extends OpMode { velocities.remove(0); } } else { + leftFront.setPower(0); + leftRear.setPower(0); + rightFront.setPower(0); + rightRear.setPower(0); + for (DcMotorEx motor : motors) { + motor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE); + } double average = 0; for (Double velocity : velocities) { average += velocity;