modify RunFlyWheel and RunFlyWheelContinuous commands
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheel.java
index 0ab2e4adf7225b1139f5bcc38c7c8d1d02b34422..d68b13eca0b71d3cc3024769ac8f56777da1cbbe 100644 (file)
@@ -1,45 +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;
 
 /**
- * Runs the fly wheel at a given speed in () for input time in seconds
+ * 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.
  *
- * @param speed
- *            in ()
- * @param time
- *            in seconds
+ * @author Shaina & Chris
  */
 public class RunFlyWheel extends Command {
-       public RunFlyWheel() {
+  private Shooter shooter = Robot.getShooter();
+  private double maxTimeOut;
+
+  private PIDController wheelController;
+  private double wheelP;
+  private double wheelI;
+  private double wheelD;
+  private double target;
+
+  public RunFlyWheel(double maxTimeOut) {
+    requires(shooter);
 
-       }
+    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.CURRENT_SHOOTING_SPEED;
+  }
 
-       // Called just before this Command runs the first time
-       @Override
-       protected void initialize() {
-       }
+  // Called just before this Command runs the first time
+  protected void initialize() {
+    this.wheelController.setSetPoint(this.target);
+  }
 
-       // Called repeatedly when this Command is scheduled to run
-       @Override
-       protected void execute() {
-       }
+  // Called repeatedly when this Command is scheduled to run
+  protected void execute() {
+    double shooterSpeed = this.wheelController
+        .calcPID(this.shooter.getShooterSpeed());
 
-       // Called once after isFinished returns true
-       @Override
-       protected void end() {
-       }
+    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+  }
 
-       // Called when another command which requires one or more of the same
-       // subsystems is scheduled to run
-       @Override
-       protected void interrupted() {
-       }
+  // Make this return true when this Command no longer needs to run execute()
+  protected boolean isFinished() {
+    return timeSinceInitialized() >= maxTimeOut;
+  }
 
-       @Override
-       protected boolean isFinished() {
-               // TODO Auto-generated method stub
-               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();
+  }
 }