From: Eric Sandoval Date: Sun, 19 Feb 2017 21:24:50 +0000 (-0800) Subject: add corrections X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=commitdiff_plain;h=refs%2Fheads%2Fshooter-code-review add corrections --- diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java index 3bd4efd..0c81f51 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java @@ -21,7 +21,7 @@ public class DecreaseShootingSpeed extends Command { @Override protected void initialize() { - shooter.CURRENT_SHOOTING_SPEED -= shooter.SHOOTING_SPEED_INCREMENT; + shooter.decrementCurrentShootingSpeed(); } diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java index 85bd3bd..1588482 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/IncreaseShootingSpeed.java @@ -21,7 +21,7 @@ public class IncreaseShootingSpeed extends Command { @Override protected void initialize() { - shooter.CURRENT_SHOOTING_SPEED += shooter.SHOOTING_SPEED_INCREMENT; + shooter.incrementCurrentShootingSpeed(); } @Override diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java index 7a2f950..1bcf897 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/ResetShootingSpeed.java @@ -20,7 +20,7 @@ public class ResetShootingSpeed extends Command { @Override protected void initialize() { - shooter.CURRENT_SHOOTING_SPEED = shooter.DEFAULT_SHOOTING_SPEED; + shooter.resetCurrentShootingSpeed(); } @Override diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheel.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheel.java index 544a815..853dff6 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheel.java @@ -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(); } diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheelContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheelContinuous.java index 79a0f23..3f15e32 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/ReverseIndexWheelContinuous.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java index a20af8e..61385f6 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java @@ -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() diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java index 2ae906c..823088e 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java index 6838354..89a0b9c 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java index cb56bf4..2f1b9fe 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java index 4869775..f5d3339 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -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; + } + }