X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FShooter.java;h=adfdb341862f933a03094392848cdfe80ec37328;hb=b70398a7d5ac5f4ce64156d84227ccb4828c0615;hp=b9ccb42dff3967cabcfd551a0d71bb7c1ca31ad9;hpb=09e509d3b1f6e73a06d62e41c5a959e6eed2e5c6;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 b9ccb42..adfdb34 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -1,23 +1,29 @@ package org.usfirst.frc.team3501.robot.subsystems; import org.usfirst.frc.team3501.robot.Constants; +import org.usfirst.frc.team3501.robot.MathLib; import org.usfirst.frc.team3501.robot.utils.HallEffectSensor; +import org.usfirst.frc.team3501.robot.utils.PIDController; import com.ctre.CANTalon; import edu.wpi.first.wpilibj.command.Subsystem; public class Shooter extends Subsystem { - public double wheelP = 0, wheelI = 0, wheelD = -0; + public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008; private static Shooter shooter; 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 = 0.75; - public static double CURRENT_SHOOTING_SPEED = DEFAULT_SHOOTING_SPEED; + private PIDController wheelController; - public static final double SHOOTING_SPEED_INCREMENT = 0.05; + private static final double RPM_THRESHOLD = 10; + private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75; + private static final double DEFAULT_SHOOTING_SPEED = 2800; // rpm + private static final double SHOOTING_SPEED_INCREMENT = 25; + + private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED; + private double currentShooterMotorValue = 0; private Shooter() { flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1); @@ -27,10 +33,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,7 +51,8 @@ public class Shooter extends Subsystem { * @param val * motor value from -1 to 1(fastest forward) */ - public void setFlyWheelMotorVal(final double val) { + public void setFlyWheelMotorVal(double val) { + val = MathLib.restrictToRange(val, 0.0, 1.0); flyWheel1.set(val); flyWheel2.set(val); } @@ -68,7 +71,8 @@ public class Shooter extends Subsystem { * @param val * motor value from -1 to 1(fastest forward) */ - public void setIndexWheelMotorVal(final double val) { + public void setIndexWheelMotorVal(double val) { + val = MathLib.restrictToRange(val, -1.0, 1.0); indexWheel.set(val); } @@ -79,20 +83,61 @@ public class Shooter extends Subsystem { indexWheel.set(0); } - public double getCurrentShootingSpeed() { - return CURRENT_SHOOTING_SPEED; - } - - public void setCurrentShootingSpeed(double Value) { - CURRENT_SHOOTING_SPEED = Value; - } - @Override protected void initDefaultCommand() { } + public double getRPMThreshold() { + return RPM_THRESHOLD; + } + public double getShooterRPM() { return hallEffect.getRPM(); } + + public void setTargetShootingSpeed(double Value) { + targetShootingSpeed = Value; + } + + public void decrementTargetShootingSpeed() { + this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT; + } + + public void incrementTargetShootingSpeed() { + this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT; + } + + public void resetTargetShootingSpeed() { + this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED; + } + + public double getTargetShootingSpeed() { + return targetShootingSpeed; + } + + public void reverseIndexWheel() { + this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE); + } + + public void runIndexWheel() { + this.setIndexWheelMotorVal(DEFAULT_INDEXING_MOTOR_VALUE); + } + + public double calculateShooterSpeed() { + this.wheelController.setSetPoint(targetShootingSpeed); + double calculatedShooterIncrement = this.wheelController + .calcPID(this.getShooterRPM()); + currentShooterMotorValue += calculatedShooterIncrement; + return currentShooterMotorValue; + } + + public void initializePIDController() { + this.wheelController = new PIDController(wheelP, wheelI, wheelD); + this.wheelController.setDoneRange(10); + this.wheelController.setMaxOutput(1.0); + this.wheelController.setMinDoneCycles(3); + this.wheelController.setSetPoint(this.targetShootingSpeed); + this.currentShooterMotorValue = 0; + } }