shooter code review changes
authorCindy Zhang <cindyzyx9@gmail.com>
Tue, 21 Feb 2017 00:07:45 +0000 (16:07 -0800)
committerCindy Zhang <cindyzyx9@gmail.com>
Tue, 21 Feb 2017 00:07:45 +0000 (16:07 -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/RunIndexWheel.java
src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index 2edc9ec2586dba2f5f8c4d1031dff36756e17f74..d105b60fea1707225e167e9fe129b5dc2b7ab887 100644 (file)
@@ -21,8 +21,7 @@ public class DecreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.setCurrentShootingSpeed(
-        shooter.getCurrentShootingSpeed() - shooter.SHOOTING_SPEED_INCREMENT);
+    shooter.decrementCurrentShootingSpeed();
   }
 
   @Override
index dcd4aa744898821d0afd9c4bb7d5df5d1ec8fea8..158848236a71a32a36447197bb55aa0cd34e1e03 100644 (file)
@@ -21,8 +21,7 @@ public class IncreaseShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.setCurrentShootingSpeed(
-        shooter.getCurrentShootingSpeed() + shooter.SHOOTING_SPEED_INCREMENT);
+    shooter.incrementCurrentShootingSpeed();
   }
 
   @Override
index d8f016218ae79a590db2d380d3d71eda13babfe8..1bcf8970b21aa80fe0984fefcf247dbab5200822 100644 (file)
@@ -20,7 +20,7 @@ public class ResetShootingSpeed extends Command {
 
   @Override
   protected void initialize() {
-    shooter.setCurrentShootingSpeed(shooter.DEFAULT_SHOOTING_SPEED);
+    shooter.resetCurrentShootingSpeed();
   }
 
   @Override
index 544a81533158ec247845a4fb5c81869d1938fa38..2ed11b6a398e97d7cdf4e28e03479a9bb1a0e818 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;
 
@@ -12,8 +13,8 @@ import edu.wpi.first.wpilibj.command.Command;
  */
 
 public class ReverseIndexWheel extends Command {
+  private Shooter shooter = Robot.getShooter();
   private double time;
-  private double motorVal;
 
   /**
    * See JavaDoc comment in class for details
@@ -24,20 +25,18 @@ public class ReverseIndexWheel extends Command {
    *          in seconds, amount of time to run index wheel motor
    */
 
-  public ReverseIndexWheel(double time, double motorVal) {
+  public ReverseIndexWheel(double time) {
     requires(Robot.getDriveTrain());
     this.time = time;
-    this.motorVal = motorVal;
   }
 
   @Override
   protected void initialize() {
-
   }
 
   @Override
   protected void execute() {
-    Robot.getShooter().setIndexWheelMotorVal(-motorVal);
+    shooter.reverseIndexWheel();
 
   }
 
@@ -48,7 +47,7 @@ public class ReverseIndexWheel extends Command {
 
   @Override
   protected void end() {
-    Robot.getShooter().stopIndexWheel();
+    shooter.stopIndexWheel();
 
   }
 
index 05ab564fe873b15a2435d10adf945c8977ba1024..4cb18f9b28b8e57061b62c3758a5ef357a975591 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.reverseIndexWheel();
   }
 
   // Called once after isFinished returns true
index 3f8baa0c3ffe2527e59701e9967115371685f979..d9966f1171494ace578ccc72ae081a5bbed46c10 100644 (file)
@@ -39,9 +39,8 @@ public class RunIndexWheel extends Command {
   @Override
   protected void execute() {
     double shooterSpeed = shooter.getShooterRPM();
-    if (shooterSpeed > 0) {
-      shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
-    }
+    if (shooterSpeed > 0)
+      shooter.runIndexWheel();
   }
 
   // Called once after isFinished returns true
index f958be7fa4788e067e93b225680d56045e08c532..da3fee1cb6bdfaf542cafe339e28d45e568ab90e 100644 (file)
@@ -39,9 +39,8 @@ public class RunIndexWheelContinuous extends Command {
   @Override
   protected void execute() {
     double shooterSpeed = shooter.getShooterRPM();
-    if (shooterSpeed > 0) {
-      shooter.setIndexWheelMotorVal(shooter.DEFAULT_INDEXING_SPEED);
-    }
+    if (shooterSpeed > 0)
+      shooter.runIndexWheel();
   }
 
   // Called once after isFinished returns true
index 391eeafce1e1a3806c2ee1e5ad3aa1a910101688..91da0989fd53f2cabead98f63f70ed67dadc6114 100644 (file)
@@ -14,11 +14,11 @@ public class Shooter extends Subsystem {
   private static HallEffectSensor hallEffect;
   private final CANTalon flyWheel1, flyWheel2, indexWheel;
 
-  public static final double DEFAULT_INDEXING_SPEED = -0.75;
-  public static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm
-  private static double CURRENT_SHOOTING_SPEED = DEFAULT_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 = 25;
+  private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
 
   private Shooter() {
     flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
@@ -28,10 +28,6 @@ public class Shooter extends Subsystem {
     hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
   }
 
-  public static HallEffectSensor getHallEffectSensor() {
-    return hallEffect;
-  }
-
   /**
    * Returns shooter object
    *
@@ -82,20 +78,40 @@ public class Shooter extends Subsystem {
     indexWheel.set(0);
   }
 
-  public double getCurrentShootingSpeed() {
-    return CURRENT_SHOOTING_SPEED;
+  @Override
+  protected void initDefaultCommand() {
+
+  }
+
+  public double getShooterRPM() {
+    return hallEffect.getRPM();
   }
 
   public void setCurrentShootingSpeed(double Value) {
-    CURRENT_SHOOTING_SPEED = Value;
+    currentShootingSpeed = Value;
   }
 
-  @Override
-  protected void initDefaultCommand() {
+  public void decrementCurrentShootingSpeed() {
+    this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT;
+  }
 
+  public void incrementCurrentShootingSpeed() {
+    this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT;
   }
 
-  public double getShooterRPM() {
-    return hallEffect.getRPM();
+  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);
   }
 }