implement tank drive and toggle winch
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / driving / TimeDrive.java
index 465840d75dbbe03f3a2dd0a388782ea86ac4a9e8..d0104a84415055d5eca765434e4feabf438e5355 100755 (executable)
@@ -5,43 +5,51 @@ import org.usfirst.frc.team3501.robot.Robot;
 import edu.wpi.first.wpilibj.Timer;
 import edu.wpi.first.wpilibj.command.Command;
 
-/**
+/***
+ * This commands make the robot drive for a specified time with the motors set
+ * at a specified value between 1 and -1
+ *
+ * parameters:
+ * time: how long the robot should drive for - in seconds
+ * motorVal: the motor input to set the motors to
+ *
  *
  */
 public class TimeDrive extends Command {
-    Timer timer;
-    double motorVal, time;
-
-    public TimeDrive(double time, double motorVal) {
-        requires(Robot.getDriveTrain());
-
-        timer = new Timer();
-        this.time = time;
-        this.motorVal = motorVal;
-    }
-
-    @Override
-    protected void initialize() {
-        timer.start();
-        Robot.getDriveTrain().setMotorValues(motorVal, motorVal);
-    }
-
-    @Override
-    protected void execute() {
-    }
-
-    @Override
-    protected boolean isFinished() {
-        return timer.get() >= time;
-    }
-
-    @Override
-    protected void end() {
-        Robot.getDriveTrain().stop();
-    }
-
-    @Override
-    protected void interrupted() {
-        end();
-    }
+  Timer timer;
+  double motorVal, time;
+
+  public TimeDrive(final double time, final double motorVal) {
+    requires(Robot.getDriveTrain());
+
+    timer = new Timer();
+    this.time = time;
+    this.motorVal = motorVal;
+  }
+
+  @Override
+  protected void initialize() {
+    timer.start();
+  }
+
+  @Override
+  protected void execute() {
+    Robot.getDriveTrain().setMotorValues(motorVal, motorVal);
+
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return timer.get() >= time;
+  }
+
+  @Override
+  protected void end() {
+    Robot.getDriveTrain().stop();
+  }
+
+  @Override
+  protected void interrupted() {
+    end();
+  }
 }