makes it brake after ending the velocity tuner
This commit is contained in:
@ -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;
|
||||
|
@ -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;
|
||||
|
Reference in New Issue
Block a user