driver practice changes
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / Shooter.java
index 0c58ba32bb7605bc5a5e0d8c6c1addd6aebcaf52..faca5ddac1c1e7b9caabab21298a932c8192e5d0 100644 (file)
@@ -1,23 +1,33 @@
 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.DoubleSolenoid;
+import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
 import edu.wpi.first.wpilibj.command.Subsystem;
 
 public class Shooter extends Subsystem {
-  public double wheelP = 0, wheelI = 0, wheelD = -0;
+  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 = 0;
-  public static final double DEFAULT_SHOOTING_SPEED = 0;
-  public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED;
+  private PIDController wheelController;
 
-  public static final double SHOOTING_SPEED_INCREMENT = 0;
+  private static final double RPM_THRESHOLD = 10;
+  private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75;
+  private static final double DEFAULT_SHOOTING_SPEED = 3100; // rpm
+  private static final double SHOOTING_SPEED_INCREMENT = 50;
+
+  private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double currentShooterMotorValue = 0;
+
+  private final DoubleSolenoid piston;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
@@ -25,10 +35,9 @@ public class Shooter extends Subsystem {
     indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
 
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
-  }
 
-  public static HallEffectSensor getHallEffectSensor() {
-    return hallEffect;
+    piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER,
+        Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE);
   }
 
   /**
@@ -49,7 +58,8 @@ public class Shooter extends Subsystem {
    * @param val
    *          motor value from -1 to 1(fastest forward)
    */
-  public void setFlyWheelMotorVal(final double val) {
+  public void setFlyWheelMotorVal(double val) {
+    val = MathLib.restrictToRange(val, 0.0, 1.0);
     flyWheel1.set(val);
     flyWheel2.set(val);
   }
@@ -68,7 +78,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);
   }
 
@@ -84,7 +95,72 @@ public class Shooter extends Subsystem {
 
   }
 
+  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 Value getPistonValue() {
+    return piston.get();
+  }
+
+  public void setHighGear() {
+    changeGear(Constants.Shooter.HIGH_GEAR);
+  }
+
+  public void setLowGear() {
+    changeGear(Constants.Shooter.LOW_GEAR);
+  }
+
+  private void changeGear(DoubleSolenoid.Value gear) {
+    piston.set(gear);
+  }
 }