code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheel.java
index 78506882140bd14c817d8f05014baa11018afb30..5abd73afe9fc64c798762a7dca6a92fd2a5b7b64 100644 (file)
@@ -2,64 +2,54 @@ package org.usfirst.frc.team3501.robot.commands.shooter;
 
 import org.usfirst.frc.team3501.robot.Robot;
 import org.usfirst.frc.team3501.robot.subsystems.Shooter;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
 
-import edu.wpi.first.wpilibj.Timer;
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
- * This command runs the fly wheel at a given speed for a given time. The fly
- * wheel is intended to shoot balls fed by the intake wheel.
+ * This command runs the fly wheel continuously at a set speed using a PID
+ * Controller when OI button managing fly wheel is pressed. The command will run
+ * the fly wheel motor until the button triggering it is released.
  *
- * @author Shaina
+ * Should only be run from the operator interface.
+ *
+ * pre-condition: This command must be run by a button in OI, with
+ * button.whileHeld(...).
+ *
+ * @author Shaina & Chris
  */
 public class RunFlyWheel extends Command {
   private Shooter shooter = Robot.getShooter();
-  Timer timer;
-  private double time;
+  double time;
 
-  /**
-   * See JavaDoc comment in class for details
-   *
-   * @param motorVal
-   *          value range from -1 to 1
-   * @param time
-   *          in seconds, amount of time to run fly wheel motor
-   */
-  public RunFlyWheel(double time) {
-    requires(shooter);
+  private PIDController wheelController;
 
-    timer = new Timer();
+  public RunFlyWheel(double time) {
     this.time = time;
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
-    timer.start();
-    shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
+    shooter.initializePIDController();
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
-  // Called once after isFinished returns true
   @Override
-  protected void end() {
-    shooter.stopFlyWheel();
+  protected boolean isFinished() {
+    return timeSinceInitialized() >= time;
   }
 
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
   @Override
-  protected void interrupted() {
-    end();
+  protected void end() {
+    this.shooter.stopFlyWheel();
   }
 
   @Override
-  protected boolean isFinished() {
-    return timer.get() >= time;
+  protected void interrupted() {
+    end();
   }
-
 }