makes it brake after ending the velocity tuner

This commit is contained in:
Anyi Lin
2024-11-28 12:38:43 -05:00
parent a4ab959de0
commit fdc7a9f979
2 changed files with 14 additions and 0 deletions

View File

@ -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;

View File

@ -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;