shooter code review changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 73c1b23282356686b7475b9ba8b21692c0753504..91da0989fd53f2cabead98f63f70ed67dadc6114 100644 (file)
@@ -1,24 +1,31 @@
 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 com.ctre.CANTalon;
 
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
+  public double wheelP = 0.0001, wheelI = 0, wheelD = 0.0004;
   private static Shooter shooter;
-  private final CANTalon flyWheel, indexWheel;
+  private static HallEffectSensor hallEffect;
+  private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_SHOOTING_SPEED = 0;
-  public static double CURRENT_SHOOTING_SPEED;
+  private static final double DEFAULT_INDEXING_SPEED = -0.75;
+  private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
+  private static final double SHOOTING_SPEED_INCREMENT = 25;
 
-  public static final double SHOOTING_SPEED_INCREMENT = 0;
+  private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
 
   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);
   }
 
   /**
@@ -39,15 +46,18 @@ public class Shooter extends Subsystem {
    * @param val
    *          motor value from -1 to 1(fastest forward)
    */
-  public void setFlyWheelMotorVal(final double val) {
-    flyWheel.set(val);
+  public void setFlyWheelMotorVal(double val) {
+    val = MathLib.restrictToRange(val, 0.0, 1.0);
+    flyWheel1.set(val);
+    flyWheel2.set(val);
   }
 
   /**
    * Stops fly wheel motor.
    */
   public void stopFlyWheel() {
-    flyWheel.set(0);
+    flyWheel1.set(0);
+    flyWheel2.set(0);
   }
 
   /**
@@ -56,7 +66,8 @@ public class Shooter extends Subsystem {
    * @param val
    *          motor value from -1 to 1(fastest forward)
    */
-  public void setIndexWheelMotorVal(final double val) {
+  public void setIndexWheelMotorVal(double val) {
+    val = MathLib.restrictToRange(val, -1.0, 1.0);
     indexWheel.set(val);
   }
 
@@ -71,4 +82,36 @@ public class Shooter extends Subsystem {
   protected void initDefaultCommand() {
 
   }
+
+  public double getShooterRPM() {
+    return hallEffect.getRPM();
+  }
+
+  public void setCurrentShootingSpeed(double Value) {
+    currentShootingSpeed = Value;
+  }
+
+  public void decrementCurrentShootingSpeed() {
+    this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+  }
+
+  public void incrementCurrentShootingSpeed() {
+    this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
+  }
+
+  public void resetCurrentShootingSpeed() {
+    this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
+  }
+
+  public double getCurrentShootingSpeed() {
+    return currentShootingSpeed;
+  }
+
+  public void reverseIndexWheel() {
+    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED);
+  }
+
+  public void runIndexWheel() {
+    this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED);
+  }
 }