X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FShooter.java;h=f5d33399b309f05577846404854469e931d982df;hb=refs%2Fheads%2Fshooter-code-review;hp=4869775e82dc88ccb8231063172da15e9839c03f;hpb=4dd20c3d051f6e39e5de6c86d04c4cade58fca59;p=3501%2F2017steamworks 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; + } + }