add corrections shooter-code-review
authorEric Sandoval <harpnart@gmail.com>
Sun, 19 Feb 2017 21:24:50 +0000 (13:24 -0800)
committerEric Sandoval <harpnart@gmail.com>
Sun, 19 Feb 2017 21:24:50 +0000 (13:24 -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/ReverseIndexWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheelContinuous.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 3bd4efd7490e7462306cbe05fb75ebff63c15516..0c81f51feaa99bfa219039fe6a3bc2bf5b63eafc 100644 (file)
@@ -21,7 +21,7 @@ public class DecreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.CURRENT_SHOOTING_SPEED -= shooter.SHOOTING_SPEED_INCREMENT;
+    shooter.decrementCurrentShootingSpeed();
 
   }
 
index 85bd3bd39dbedf9af5418853babcdb49edf7a4b4..158848236a71a32a36447197bb55aa0cd34e1e03 100644 (file)
@@ -21,7 +21,7 @@ public class IncreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.CURRENT_SHOOTING_SPEED += shooter.SHOOTING_SPEED_INCREMENT;
+    shooter.incrementCurrentShootingSpeed();
   }
 
   @Override
index 7a2f95091bcd4f79c1116f072734b2728901c763..1bcf8970b21aa80fe0984fefcf247dbab5200822 100644 (file)
@@ -20,7 +20,7 @@ public class ResetShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.CURRENT_SHOOTING_SPEED = shooter.DEFAULT_SHOOTING_SPEED;
+    shooter.resetCurrentShootingSpeed();
   }
 
   @Override
index 544a81533158ec247845a4fb5c81869d1938fa38..853dff694da97cfdbd487bb97b913125015a79f2 100644 (file)
@@ -1,6 +1,7 @@
 package org.usfirst.frc.team3501.robot.commands.shooter;
 
 import org.usfirst.frc.team3501.robot.Robot;
+import org.usfirst.frc.team3501.robot.subsystems.Shooter;
 
 import edu.wpi.first.wpilibj.command.Command;
 
@@ -14,6 +15,7 @@ import edu.wpi.first.wpilibj.command.Command;
 public class ReverseIndexWheel extends Command {
   private double time;
   private double motorVal;
+  private Shooter shooter = Robot.getShooter();
 
   /**
    * See JavaDoc comment in class for details
@@ -37,7 +39,7 @@ public class ReverseIndexWheel extends Command {
 
   @Override
   protected void execute() {
-    Robot.getShooter().setIndexWheelMotorVal(-motorVal);
+    shooter.runIndexWheelReverse();
 
   }
 
index 79a0f237f18e368ea6dc165e5e525f60b00c44e0..3f15e32c0aba9395fe185b0395f37c20647090f8 100644 (file)
@@ -38,7 +38,7 @@ public class ReverseIndexWheelContinuous extends Command {
   // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED * -1);
+    shooter.runIndexWheelReverse();
   }
 
   // Called once after isFinished returns true
index a20af8e63badd3bfee9722e5037c9771b60a8a52..61385f69f5fd8140f3c2d2bdcd4fd22012704211 100644 (file)
@@ -26,15 +26,15 @@ public class RunFlyWheel extends Command {
 
   public RunFlyWheel(double maxTimeOut) {
 
-    this.wheelP = this.shooter.wheelP;
-    this.wheelI = this.shooter.wheelI;
-    this.wheelD = this.shooter.wheelD;
+    this.wheelP = this.shooter.getWheelP();
+    this.wheelI = this.shooter.getWheelI();
+    this.wheelD = this.shooter.getWheelD();
     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.CURRENT_SHOOTING_SPEED;
+    this.target = this.shooter.getShootingSpeed();
   }
 
   // Called just before this Command runs the first time
@@ -49,7 +49,7 @@ public class RunFlyWheel extends Command {
     double shooterSpeed = this.wheelController
         .calcPID(this.shooter.getShooterRPM());
 
-    this.shooter.setFlyWheelMotorVal(shooterSpeed);
+    this.shooter.runFlyWheel();
   }
 
   // Make this return true when this Command no longer needs to run execute()
index 2ae906c7be9753d2ba15de5b2994ccf765273a06..823088e5a00603b635f8a0888c52301ac85ee637 100644 (file)
@@ -28,15 +28,15 @@ public class RunFlyWheelContinuous extends Command {
   private double target;
 
   public RunFlyWheelContinuous() {
-    this.wheelP = this.shooter.wheelP;
-    this.wheelI = this.shooter.wheelI;
-    this.wheelD = this.shooter.wheelD;
+    this.wheelP = this.shooter.getWheelP();
+    this.wheelI = this.shooter.getWheelI();
+    this.wheelD = this.shooter.getWheelD();
     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.CURRENT_SHOOTING_SPEED;
+    this.target = this.shooter.getShootingSpeed();
   }
 
   @Override
@@ -51,7 +51,7 @@ public class RunFlyWheelContinuous extends Command {
     //
     // this.shooter.setFlyWheelMotorVal(shooterSpeed);
     System.out.println(shooter.getShooterRPM());
-    this.shooter.setFlyWheelMotorVal(this.shooter.CURRENT_SHOOTING_SPEED);
+    this.shooter.runFlyWheel();
   }
 
   @Override
index 68383544bf95779ff7b7b79f887703b9a8942a83..89a0b9c2b00b106752e9462c3e064ef3a97ed906 100644 (file)
@@ -38,7 +38,7 @@ public class RunIndexWheel extends Command {
   // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
+    shooter.runIndexWheelForward();
   }
 
   // Called once after isFinished returns true
index cb56bf42f4e2b1b53cbbaf35a0e3c15bd8c29293..2f1b9fecc07f90795dd0c5a7acaf038a86e05d1c 100644 (file)
@@ -38,7 +38,7 @@ public class RunIndexWheelContinuous extends Command {
   // Called repeatedly when this Command is scheduled to run
   @Override
   protected void execute() {
-    shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
+    shooter.runIndexWheelForward();
   }
 
   // Called once after isFinished returns true
index 4869775e82dc88ccb8231063172da15e9839c03f..f5d33399b309f05577846404854469e931d982df 100644 (file)
@@ -8,16 +8,16 @@ 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 static HallEffectSensor hallEffect;
+  private HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_INDEXING_SPEED = -0.75;
-  public static final double DEFAULT_SHOOTING_SPEED = 0.75;
-  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.05;
+  private static final double SHOOTING_SPEED_INCREMENT = 0.05;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
@@ -27,10 +27,6 @@ public class Shooter extends Subsystem {
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
   }
 
-  public static HallEffectSensor getHallEffectSensor() {
-    return hallEffect;
-  }
-
   /**
    * Returns shooter object
    *
@@ -49,11 +45,19 @@ public class Shooter extends Subsystem {
    * @param val
    *          motor value from -1 to 1(fastest forward)
    */
-  public void setFlyWheelMotorVal(final double 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.
    */
@@ -63,20 +67,24 @@ public class Shooter extends Subsystem {
   }
 
   /**
-   * Sets index wheel motor value to input.
-   *
-   * @param val
-   *          motor value from -1 to 1(fastest forward)
+   * Stops index wheel motor.
    */
-  public void setIndexWheelMotorVal(final double val) {
-    indexWheel.set(val);
+  public void stopIndexWheel() {
+    indexWheel.set(0);
   }
 
   /**
-   * Stops index wheel motor.
+   * Run the index wheel forwards
    */
-  public void stopIndexWheel() {
-    indexWheel.set(0);
+  public void runIndexWheelForward() {
+    indexWheel.set(currentShootingSpeed);
+  }
+
+  /**
+   * Run the index wheel backwards
+   */
+  public void runIndexWheelReverse() {
+    indexWheel.set(-currentShootingSpeed);
   }
 
   @Override
@@ -87,4 +95,42 @@ public class Shooter extends Subsystem {
   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;
+  }
+
 }