add corrections
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 150ce5091a27713f73a63b970f06ee1274daa138..f5d33399b309f05577846404854469e931d982df 100644 (file)
@@ -1,26 +1,30 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
+import org.usfirst.frc.team3501.robot.utils.HallEffectSensor;
 
 import com.ctre.CANTalon;
 
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  public double wheelP = 0, wheelI = 0, wheelD = -0;
+  private double wheelP = 0, wheelI = 0, wheelD = -0;
   private static Shooter shooter;
-  private final CANTalon flyWheel, indexWheel;
+  private HallEffectSensor hallEffect;
+  private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_INDEXING_SPEED = 0;
-  public static final double DEFAULT_SHOOTING_SPEED = 0;
-  public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
+  private static final double DEFAULT_INDEXING_SPEED = -0.75;
+  private static final double DEFAULT_SHOOTING_SPEED = 0.75;
+  private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
 
-  public static final double SHOOTING_SPEED_INCREMENT = 0;
+  private static final double SHOOTING_SPEED_INCREMENT = 0.05;
 
   private Shooter() {
-    flyWheel = new CANTalon(Constants.Shooter.FLY_WHEEL);
+    flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
+    flyWheel2 = new CANTalon(Constants.Shooter.FLY_WHEEL2);
     indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
 
+    hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
   }
 
   /**
@@ -41,32 +45,46 @@ public class Shooter extends Subsystem {
    * @param val
    *          motor value from -1 to 1(fastest forward)
    */
-  public void setFlyWheelMotorVal(final double val) {
-    flyWheel.set(val);
+  private void setFlyWheelMotorVal(final double val) {
+    flyWheel1.set(val);
+    flyWheel2.set(val);
+  }
+
+  public void incrementCurrentShootingSpeed() {
+    currentShootingSpeed += SHOOTING_SPEED_INCREMENT;
+  }
+
+  public void runFlyWheel() {
+    flyWheel1.set(currentShootingSpeed);
   }
 
   /**
    * Stops fly wheel motor.
    */
   public void stopFlyWheel() {
-    flyWheel.set(0);
+    flyWheel1.set(0);
+    flyWheel2.set(0);
   }
 
   /**
-   * Sets index wheel motor value to input.
-   *
-   * @param val
-   *          motor value from -1 to 1(fastest forward)
+   * Stops index wheel motor.
+   */
+  public void stopIndexWheel() {
+    indexWheel.set(0);
+  }
+
+  /**
+   * Run the index wheel forwards
    */
-  public void setIndexWheelMotorVal(final double val) {
-    indexWheel.set(val);
+  public void runIndexWheelForward() {
+    indexWheel.set(currentShootingSpeed);
   }
 
   /**
-   * Stops index wheel motor.
+   * Run the index wheel backwards
    */
-  public void stopIndexWheel() {
-    indexWheel.set(0);
+  public void runIndexWheelReverse() {
+    indexWheel.set(-currentShootingSpeed);
   }
 
   @Override
@@ -74,7 +92,45 @@ public class Shooter extends Subsystem {
 
   }
 
-  public double getShooterSpeed() {
-    return 0.0;
+  public double getShooterRPM() {
+    return hallEffect.getRPM();
+  }
+
+  public void decrementCurrentShootingSpeed() {
+    currentShootingSpeed -= SHOOTING_SPEED_INCREMENT;
+
   }
+
+  public void resetCurrentShootingSpeed() {
+    currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  }
+
+  /**
+   * @return the wheelP
+   */
+  public double getWheelP() {
+    return wheelP;
+  }
+
+  /**
+   * @return the wheelI
+   */
+  public double getWheelI() {
+    return wheelI;
+  }
+
+  /**
+   * @return the wheelD
+   */
+  public double getWheelD() {
+    return wheelD;
+  }
+
+  /**
+   * @return the currentShootingSpeed
+   */
+  public double getShootingSpeed() {
+    return currentShootingSpeed;
+  }
+
 }