implement shooter pid
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheel.java
index cda56a73480f1934b266e727a99aa82ccf312c74..c5101fc7d0dea5e23353b3a6c6b890ad35247450 100644 (file)
@@ -1,39 +1,68 @@
+
 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 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 at a specific speed using a PID Controller
+ * for accuracy for a given time. The fly wheel is intended to shoot balls fed
+ * by the intake wheel.
  *
- * @param motorVal
- *          [-1,1]
- * @param time
- *          in seconds
- * @author Shaina
+ * @author Shaina & Chris
  */
 public class RunFlyWheel extends Command {
-  private double motorVal;
-  private double time;
+  private Shooter shooter = Robot.getShooter();
+  private double maxTimeOut;
+
+  private PIDController wheelController;
+  private double wheelP;
+  private double wheelI;
+  private double wheelD;
+  private double target;
+  private double shooterSpeed = 0;
+
+  public RunFlyWheel(double maxTimeOut) {
 
-  public RunFlyWheel(double motorVal, double time) {
-    this.motorVal = motorVal;
-    this.time = time;
+    this.wheelP = this.shooter.wheelP;
+    this.wheelI = this.shooter.wheelI;
+    this.wheelD = this.shooter.wheelD;
+    this.wheelController = new PIDController(this.wheelP, this.wheelI,
+        this.wheelD);
+    this.wheelController.setDoneRange(0.5);
+    this.wheelController.setMaxOutput(1.0);
+    this.wheelController.setMinDoneCycles(3);
+    this.target = this.shooter.getCurrentShootingSpeed();
   }
 
   // Called just before this Command runs the first time
   @Override
   protected void initialize() {
+    this.wheelController.setSetPoint(this.target);
   }
 
   // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
+    double calculatedShooterIncrement = this.wheelController
+        .calcPID(this.shooter.getShooterRPM());
+    shooterSpeed += calculatedShooterIncrement;
+    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return timeSinceInitialized() >= maxTimeOut;
   }
 
   // Called once after isFinished returns true
   @Override
   protected void end() {
+    this.shooter.stopFlyWheel();
   }
 
   // Called when another command which requires one or more of the same
@@ -41,10 +70,4 @@ public class RunFlyWheel extends Command {
   @Override
   protected void interrupted() {
   }
-
-  @Override
-  protected boolean isFinished() {
-    return false;
-  }
-
 }