competition fixes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 7a11c2d74440abff3dea25a9c2e60adbaad0e4d4..ab36fddee10a8be135c5589ef4c1a8b5baa8d0e2 100644 (file)
@@ -3,22 +3,28 @@ package org.usfirst.frc.team3501.robot.subsystems;
 import org.usfirst.frc.team3501.robot.Constants;
 import org.usfirst.frc.team3501.robot.MathLib;
 import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
 
 import com.ctre.CANTalon;
 
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  public double wheelP = 0.0003, wheelI = 0, wheelD = -0.00004;
+  public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008;
   private static Shooter shooter;
   private static HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_INDEXING_SPEED = -1.0;
-  public static final double DEFAULT_SHOOTING_SPEED = 0.75;
-  public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
+  private PIDController wheelController;
 
-  public static final double SHOOTING_SPEED_INCREMENT = 0.05;
+  private static final double RPM_THRESHOLD = 10;
+  private static final double DEFAULT_INDEXING_MOTOR_VALUE = 0.75;
+  private static final double REVERSE_FLYWHEEL_MOTOR_VALUE = -0.75;
+  private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
+  private static final double SHOOTING_SPEED_INCREMENT = 50;
+
+  private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double currentShooterMotorValue = 0;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
@@ -28,10 +34,6 @@ public class Shooter extends Subsystem {
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
   }
 
-  public static HallEffectSensor getHallEffectSensor() {
-    return hallEffect;
-  }
-
   /**
    * Returns shooter object
    *
@@ -51,7 +53,7 @@ public class Shooter extends Subsystem {
    *          motor value from -1 to 1(fastest forward)
    */
   public void setFlyWheelMotorVal(double val) {
-    val = MathLib.restrictToRange(val, 0.0, 1.0);
+    val = MathLib.restrictToRange(val, -1.0, 1.0);
     flyWheel1.set(val);
     flyWheel2.set(val);
   }
@@ -82,20 +84,65 @@ public class Shooter extends Subsystem {
     indexWheel.set(0);
   }
 
-  public double getCurrentShootingSpeed() {
-    return CURRENT_SHOOTING_SPEED;
-  }
-
-  public void setCurrentShootingSpeed(double Value) {
-    CURRENT_SHOOTING_SPEED = Value;
-  }
-
   @Override
   protected void initDefaultCommand() {
 
   }
 
+  public double getRPMThreshold() {
+    return RPM_THRESHOLD;
+  }
+
   public double getShooterRPM() {
     return hallEffect.getRPM();
   }
+
+  public void setTargetShootingSpeed(double Value) {
+    targetShootingSpeed = Value;
+  }
+
+  public void decrementTargetShootingSpeed() {
+    this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+  }
+
+  public void incrementTargetShootingSpeed() {
+    this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
+  }
+
+  public void resetTargetShootingSpeed() {
+    this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
+  }
+
+  public double getTargetShootingSpeed() {
+    return targetShootingSpeed;
+  }
+
+  public void reverseIndexWheel() {
+    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE);
+  }
+
+  public void runIndexWheel() {
+    this.setIndexWheelMotorVal(DEFAULT_INDEXING_MOTOR_VALUE);
+  }
+
+  public double calculateShooterSpeed() {
+    this.wheelController.setSetPoint(targetShootingSpeed);
+    double calculatedShooterIncrement = this.wheelController
+        .calcPID(this.getShooterRPM());
+    currentShooterMotorValue += calculatedShooterIncrement;
+    return currentShooterMotorValue;
+  }
+
+  public void initializePIDController() {
+    this.wheelController = new PIDController(wheelP, wheelI, wheelD);
+    this.wheelController.setDoneRange(10);
+    this.wheelController.setMaxOutput(1.0);
+    this.wheelController.setMinDoneCycles(3);
+    this.wheelController.setSetPoint(this.targetShootingSpeed);
+    this.currentShooterMotorValue = 0;
+  }
+
+  public void reverseFlyWheel() {
+    this.setFlyWheelMotorVal(shooter.REVERSE_FLYWHEEL_MOTOR_VALUE);
+  }
 }