enable DriveDistance to drive backwards
authorDavid <david.dobervich@gmail.com>
Fri, 20 Nov 2015 18:55:36 +0000 (10:55 -0800)
committerDavid <david.dobervich@gmail.com>
Fri, 20 Nov 2015 18:55:36 +0000 (10:55 -0800)
src/org/usfirst/frc3501/RiceCatRobot/commands/DriveDistance.java

index 75ae227b9e8bfb6602e779e00956ecddbc36b580..461050e5d8ec965839485b7ef37fedea92b95fba 100644 (file)
@@ -19,7 +19,9 @@ public class DriveDistance extends Command {
     // Since negative values in setMotorSpeeds(...) are forwards, we reverse
     // speed here so positive input values will move the robot forwards.
     this.speed = -speed;
-    this.distance = distance;
+
+    // ensure distance is positive
+    this.distance = Math.max(distance, -distance);
   }
 
   @Override
@@ -35,8 +37,8 @@ public class DriveDistance extends Command {
 
   @Override
   protected boolean isFinished() {
-    return Robot.driveTrain.getLeftDistance() >= distance
-        && Robot.driveTrain.getRightDistance() >= distance;
+    return Math.abs(Robot.driveTrain.getLeftDistance()) >= distance
+        && Math.abs(Robot.driveTrain.getRightDistance()) >= distance;
   }
 
   @Override