code review changes
authorCindy Zhang <cindyzyx9@gmail.com>
Tue, 21 Feb 2017 18:18:47 +0000 (10:18 -0800)
committerCindy Zhang <cindyzyx9@gmail.com>
Tue, 21 Feb 2017 18:18:47 +0000 (10:18 -0800)
src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index d105b60fea1707225e167e9fe129b5dc2b7ab887..7fa6cd0422aa3ab3fdaff86b2bcbff450050d9f7 100644 (file)
@@ -21,7 +21,7 @@ public class DecreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.decrementCurrentShootingSpeed();
+    shooter.decrementTargetShootingSpeed();
   }
 
   @Override
index 158848236a71a32a36447197bb55aa0cd34e1e03..8a2fbd99b4f868fc0c0e8a39862cb20dfd58e57d 100644 (file)
@@ -21,7 +21,7 @@ public class IncreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.incrementCurrentShootingSpeed();
+    shooter.incrementTargetShootingSpeed();
   }
 
   @Override
index 1bcf8970b21aa80fe0984fefcf247dbab5200822..8eb98bb90f26974f900ddbcb83486ad99859373b 100644 (file)
@@ -20,7 +20,7 @@ public class ResetShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.resetCurrentShootingSpeed();
+    shooter.resetTargetShootingSpeed();
   }
 
   @Override
index c5101fc7d0dea5e23353b3a6c6b890ad35247450..5abd73afe9fc64c798762a7dca6a92fd2a5b7b64 100644 (file)
@@ -1,4 +1,3 @@
-
 package org.usfirst.frc.team3501.robot.commands.shooter;
 
 import org.usfirst.frc.team3501.robot.Robot;
@@ -8,66 +7,49 @@ import org.usfirst.frc.team3501.robot.utils.PIDController;
 import edu.wpi.first.wpilibj.command.Command;
 
 /**
- * This command runs the fly wheel at a specific speed using a PID Controller
- * for accuracy for a given time. The fly wheel is intended to shoot balls fed
- * by the intake wheel.
+ * This command runs the fly wheel continuously at a set speed using a PID
+ * Controller when OI button managing fly wheel is pressed. The command will run
+ * the fly wheel motor until the button triggering it is released.
+ *
+ * Should only be run from the operator interface.
+ *
+ * pre-condition: This command must be run by a button in OI, with
+ * button.whileHeld(...).
  *
  * @author Shaina & Chris
  */
 public class RunFlyWheel extends Command {
   private Shooter shooter = Robot.getShooter();
-  private double maxTimeOut;
+  double time;
 
   private PIDController wheelController;
-  private double wheelP;
-  private double wheelI;
-  private double wheelD;
-  private double target;
-  private double shooterSpeed = 0;
-
-  public RunFlyWheel(double maxTimeOut) {
 
-    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.getCurrentShootingSpeed();
+  public RunFlyWheel(double time) {
+    this.time = time;
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
-    this.wheelController.setSetPoint(this.target);
+    shooter.initializePIDController();
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    double calculatedShooterIncrement = this.wheelController
-        .calcPID(this.shooter.getShooterRPM());
-    shooterSpeed += calculatedShooterIncrement;
-    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
-  // Make this return true when this Command no longer needs to run execute()
   @Override
   protected boolean isFinished() {
-    return timeSinceInitialized() >= maxTimeOut;
+    return timeSinceInitialized() >= time;
   }
 
-  // Called once after isFinished returns true
   @Override
   protected void end() {
     this.shooter.stopFlyWheel();
   }
 
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
   @Override
   protected void interrupted() {
+    end();
   }
 }
index fa5426e90a21580e42d14c76e7f2d98ef9ac72ed..86c31f7eecd523ebc2a274a6b4d1d58bb74d45ed 100644 (file)
@@ -22,35 +22,18 @@ public class RunFlyWheelContinuous extends Command {
   private Shooter shooter = Robot.getShooter();
 
   private PIDController wheelController;
-  private double wheelP;
-  private double wheelI;
-  private double wheelD;
-  private double target;
-  private double shooterSpeed = 0;
 
   public RunFlyWheelContinuous() {
-    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(10);
-    this.wheelController.setMaxOutput(1.0);
-    this.wheelController.setMinDoneCycles(3);
-    this.target = shooter.getCurrentShootingSpeed();
   }
 
   @Override
   protected void initialize() {
-    this.wheelController.setSetPoint(this.target);
+    shooter.initializePIDController();
   }
 
   @Override
   protected void execute() {
-    double calculatedShooterIncrement = this.wheelController
-        .calcPID(this.shooter.getShooterRPM());
-    shooterSpeed += calculatedShooterIncrement;
-    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+    shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
   }
 
   @Override
index d9966f1171494ace578ccc72ae081a5bbed46c10..6abb095b60a0a5ac74de61627244f479ae2248f6 100644 (file)
@@ -39,7 +39,9 @@ public class RunIndexWheel extends Command {
   @Override
   protected void execute() {
     double shooterSpeed = shooter.getShooterRPM();
-    if (shooterSpeed > 0)
+    double targetShooterSpeed = shooter.getTargetShootingSpeed();
+    double threshold = shooter.getRPMThreshold();
+    if (Math.abs(shooterSpeed - targetShooterSpeed) <= threshold)
       shooter.runIndexWheel();
   }
 
index da3fee1cb6bdfaf542cafe339e28d45e568ab90e..08ead3ac4bb6b52dfb8fd9cc974fd9d80d85724f 100644 (file)
@@ -1,5 +1,6 @@
 package org.usfirst.frc.team3501.robot.commands.shooter;
 
+import org.usfirst.frc.team3501.robot.Constants;
 import org.usfirst.frc.team3501.robot.Robot;
 import org.usfirst.frc.team3501.robot.subsystems.Shooter;
 
@@ -22,35 +23,41 @@ public class RunIndexWheelContinuous extends Command {
 
   /**
    * See JavaDoc comment in class for details
-   *
-   * @param motorVal
-   *          value range from -1 to 1
    */
   public RunIndexWheelContinuous() {
     requires(shooter);
   }
 
-  // Called just before this Command runs the first time
   @Override
   protected void initialize() {
   }
 
-  // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
     double shooterSpeed = shooter.getShooterRPM();
-    if (shooterSpeed > 0)
-      shooter.runIndexWheel();
+    double targetShooterSpeed = shooter.getTargetShootingSpeed();
+    double threshold = shooter.getRPMThreshold();
+    // if (Math.abs(shooterSpeed - targetShooterSpeed) <= threshold)
+
+    if (timeSinceInitialized() % 0.5 <= 0.02) {
+
+      if (Robot.getDriveTrain()
+          .getLeftGearPistonValue() == Constants.DriveTrain.LOW_GEAR) {
+        System.out.println("shifting to low gear " + timeSinceInitialized());
+        Robot.getDriveTrain().setHighGear();
+      } else {
+        System.out.println("shifting to high gear " + timeSinceInitialized());
+        Robot.getDriveTrain().setLowGear();
+      }
+    }
+    shooter.runIndexWheel();
   }
 
-  // Called once after isFinished returns true
   @Override
   protected void end() {
     shooter.stopIndexWheel();
   }
 
-  // Called when another command which requires one or more of the same
-  // subsystems is scheduled to run
   @Override
   protected void interrupted() {
     end();
index 91da0989fd53f2cabead98f63f70ed67dadc6114..6397292049a78637fe675af773033a382d605268 100644 (file)
@@ -3,22 +3,27 @@ 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.0001, wheelI = 0, wheelD = 0.0004;
+  public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008;
   private static Shooter shooter;
   private static HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  private static final double DEFAULT_INDEXING_SPEED = -0.75;
+  private PIDController wheelController;
+
+  private static final double RPM_THRESHOLD = 10;
+  private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75;
   private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
   private static final double SHOOTING_SPEED_INCREMENT = 25;
 
-  private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+  private double currentShooterMotorValue = 0;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
@@ -83,35 +88,56 @@ public class Shooter extends Subsystem {
 
   }
 
+  public double getRPMThreshold() {
+    return RPM_THRESHOLD;
+  }
+
   public double getShooterRPM() {
     return hallEffect.getRPM();
   }
 
-  public void setCurrentShootingSpeed(double Value) {
-    currentShootingSpeed = Value;
+  public void setTargetShootingSpeed(double Value) {
+    targetShootingSpeed = Value;
   }
 
-  public void decrementCurrentShootingSpeed() {
-    this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+  public void decrementTargetShootingSpeed() {
+    this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
   }
 
-  public void incrementCurrentShootingSpeed() {
-    this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
+  public void incrementTargetShootingSpeed() {
+    this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
   }
 
-  public void resetCurrentShootingSpeed() {
-    this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
+  public void resetTargetShootingSpeed() {
+    this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED;
   }
 
-  public double getCurrentShootingSpeed() {
-    return currentShootingSpeed;
+  public double getTargetShootingSpeed() {
+    return targetShootingSpeed;
   }
 
   public void reverseIndexWheel() {
-    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED);
+    this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE);
   }
 
   public void runIndexWheel() {
-    this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED);
+    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;
   }
 }