make code for pid fly wheel control
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / StartUpFlyWheel.java
index 97f07e64d2eda0f5c68e8e4741530ff3a2f80529..414641b9ea075d272d1951ef331d9f877d15268d 100644 (file)
@@ -1,36 +1,72 @@
 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;
 
 /**
  *
  */
 public class StartUpFlyWheel extends Command {
+  private Shooter shooter = Robot.getShooter();
+  private double maxTimeOut;
 
-    public StartUpFlyWheel() {
-        // Use requires() here to declare subsystem dependencies
-        // eg. requires(chassis);
-    }
+  private PIDController wheelController;
+  private double wheelP;
+  private double wheelI;
+  private double wheelD;
+  private double motorVal;
+  private double target;
 
-    // Called just before this Command runs the first time
-    protected void initialize() {
-    }
+  public StartUpFlyWheel(double speed, double maxTimeOut) {
+    // Use requires() here to declare subsystem dependencies
+    // eg. requires(chassis);
+    requires(shooter);
 
-    // Called repeatedly when this Command is scheduled to run
-    protected void execute() {
-    }
+    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 = speed;
+  }
 
-    // Make this return true when this Command no longer needs to run execute()
-    protected boolean isFinished() {
-        return false;
-    }
+  // Called just before this Command runs the first time
+  protected void initialize() {
+    this.wheelController.setSetPoint(this.target);
+  }
 
-    // Called once after isFinished returns true
-    protected void end() {
-    }
+  // Called repeatedly when this Command is scheduled to run
+  protected void execute() {
+    double shooterSpeed = this.wheelController
+        .calcPID(this.shooter.getShooterSpeed());
+
+    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+  }
 
-    // Called when another command which requires one or more of the same
-    // subsystems is scheduled to run
-    protected void interrupted() {
+  // Make this return true when this Command no longer needs to run execute()
+  protected boolean isFinished() {
+    boolean isDone = this.wheelController.isDone();
+    if (timeSinceInitialized() >= maxTimeOut || isDone) {
+      System.out.println("time: " + timeSinceInitialized());
+      return true;
     }
+    return false;
+  }
+
+  // Called once after isFinished returns true
+  protected void end() {
+    this.shooter.stopFlyWheel();
+  }
+
+  // Called when another command which requires one or more of the same
+  // subsystems is scheduled to run
+  protected void interrupted() {
+    end();
+  }
 }