middle of tuning
This commit is contained in:
@@ -416,7 +416,7 @@ class ForwardVelocityTuner extends OpMode {
|
|||||||
|
|
||||||
|
|
||||||
if (!end) {
|
if (!end) {
|
||||||
if (Math.abs(follower.getPose().getX()) > (DISTANCE + 72)) {
|
if (Math.abs(follower.getPose().getX()) > (DISTANCE)) {
|
||||||
end = true;
|
end = true;
|
||||||
stopRobot();
|
stopRobot();
|
||||||
} else {
|
} else {
|
||||||
@@ -524,7 +524,7 @@ class LateralVelocityTuner extends OpMode {
|
|||||||
drawCurrentAndHistory();
|
drawCurrentAndHistory();
|
||||||
|
|
||||||
if (!end) {
|
if (!end) {
|
||||||
if (Math.abs(follower.getPose().getY()) > (DISTANCE + 72)) {
|
if (Math.abs(follower.getPose().getY()) > (DISTANCE)) {
|
||||||
end = true;
|
end = true;
|
||||||
stopRobot();
|
stopRobot();
|
||||||
} else {
|
} else {
|
||||||
|
|||||||
Reference in New Issue
Block a user