From f625e57a09b295f7d40e4568a8e3a8cd125630aa Mon Sep 17 00:00:00 2001 From: Cindy Zhang Date: Mon, 20 Feb 2017 16:07:45 -0800 Subject: [PATCH] shooter code review changes --- .../shooter/DecreaseShootingSpeed.java | 3 +- .../shooter/IncreaseShootingSpeed.java | 3 +- .../commands/shooter/ResetShootingSpeed.java | 2 +- .../commands/shooter/ReverseIndexWheel.java | 11 ++--- .../shooter/ReverseIndexWheelContinuous.java | 2 +- .../robot/commands/shooter/RunIndexWheel.java | 5 +- .../shooter/RunIndexWheelContinuous.java | 5 +- .../team3501/robot/subsystems/Shooter.java | 46 +++++++++++++------ 8 files changed, 44 insertions(+), 33 deletions(-) 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 2edc9ec..d105b60 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/DecreaseShootingSpeed.java @@ -21,8 +21,7 @@ public class DecreaseShootingSpeed extends Command { @Override protected void initialize() { - shooter.setCurrentShootingSpeed( - shooter.getCurrentShootingSpeed() - shooter.SHOOTING_SPEED_INCREMENT); + shooter.decrementCurrentShootingSpeed(); } @Override 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 dcd4aa7..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,8 +21,7 @@ public class IncreaseShootingSpeed extends Command { @Override protected void initialize() { - shooter.setCurrentShootingSpeed( - shooter.getCurrentShootingSpeed() + 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 d8f0162..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.setCurrentShootingSpeed(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..2ed11b6 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; @@ -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(); } 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 05ab564..4cb18f9 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.reverseIndexWheel(); } // Called once after isFinished returns true 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 3f8baa0..d9966f1 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheel.java @@ -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 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 f958be7..da3fee1 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunIndexWheelContinuous.java @@ -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 diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java index 391eeaf..91da098 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -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); } } -- 2.30.2