code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheelContinuous.java
index af77483c85939ffa7205610078a4ee2630275805..86c31f7eecd523ebc2a274a6b4d1d58bb74d45ed 100644 (file)
@@ -2,60 +2,52 @@ 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.command.Command;
 
 /**
- * This command runs the fly wheel continuously when OI button managing fly
- * wheel is pressed. The command will run the fly wheel motor until the button
- * triggering it is released.
+ * 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.
  *
  * 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
+ * @author Shaina & Chris
  */
 public class RunFlyWheelContinuous extends Command {
   private Shooter shooter = Robot.getShooter();
 
-  /**
-   * See JavaDoc comment in class for details
-   *
-   * @param motorVal
-   *          value range from -1 to 1
-   */
+  private PIDController wheelController;
+
   public RunFlyWheelContinuous() {
-    requires(shooter);
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
+    shooter.initializePIDController();
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
-  // Called once after isFinished returns true
   @Override
-  protected void end() {
+  protected boolean isFinished() {
+    return false;
   }
 
-  // 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 !Robot.getOI().toggleFlyWheel.get();
+  protected void interrupted() {
+    end();
   }
-
 }