X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fsubsystems%2FShooter.java;h=ab36fddee10a8be135c5589ef4c1a8b5baa8d0e2;hb=9ca89e45fa84b2ec93bc6adf60c7dde1e0a7defb;hp=91da0989fd53f2cabead98f63f70ed67dadc6114;hpb=f625e57a09b295f7d40e4568a8e3a8cd125630aa;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 91da098..ab36fdd 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java @@ -3,22 +3,28 @@ 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.0001, wheelI = 0, wheelD = 0.0004; + public double wheelP = 0.00007, wheelI = 0, wheelD = 0.0008; private static Shooter shooter; private static HallEffectSensor hallEffect; private final CANTalon flyWheel1, flyWheel2, indexWheel; - private static final double DEFAULT_INDEXING_SPEED = -0.75; + private PIDController wheelController; + + private static final double RPM_THRESHOLD = 10; + private static final double DEFAULT_INDEXING_MOTOR_VALUE = 0.75; + private static final double REVERSE_FLYWHEEL_MOTOR_VALUE = -0.75; private static final double DEFAULT_SHOOTING_SPEED = 2700; // rpm - private static final double SHOOTING_SPEED_INCREMENT = 25; + private static final double SHOOTING_SPEED_INCREMENT = 50; - private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED; + private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED; + private double currentShooterMotorValue = 0; private Shooter() { flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1); @@ -47,7 +53,7 @@ public class Shooter extends Subsystem { * motor value from -1 to 1(fastest forward) */ public void setFlyWheelMotorVal(double val) { - val = MathLib.restrictToRange(val, 0.0, 1.0); + val = MathLib.restrictToRange(val, -1.0, 1.0); flyWheel1.set(val); flyWheel2.set(val); } @@ -83,35 +89,60 @@ public class Shooter extends Subsystem { } + public double getRPMThreshold() { + return RPM_THRESHOLD; + } + public double getShooterRPM() { return hallEffect.getRPM(); } - public void setCurrentShootingSpeed(double Value) { - currentShootingSpeed = Value; + public void setTargetShootingSpeed(double Value) { + targetShootingSpeed = Value; } - public void decrementCurrentShootingSpeed() { - this.currentShootingSpeed -= this.SHOOTING_SPEED_INCREMENT; + public void decrementTargetShootingSpeed() { + this.targetShootingSpeed -= this.SHOOTING_SPEED_INCREMENT; } - public void incrementCurrentShootingSpeed() { - this.currentShootingSpeed += this.SHOOTING_SPEED_INCREMENT; + public void incrementTargetShootingSpeed() { + this.targetShootingSpeed += this.SHOOTING_SPEED_INCREMENT; } - public void resetCurrentShootingSpeed() { - this.currentShootingSpeed = this.DEFAULT_SHOOTING_SPEED; + public void resetTargetShootingSpeed() { + this.targetShootingSpeed = this.DEFAULT_SHOOTING_SPEED; } - public double getCurrentShootingSpeed() { - return currentShootingSpeed; + public double getTargetShootingSpeed() { + return targetShootingSpeed; } public void reverseIndexWheel() { - this.setIndexWheelMotorVal(-DEFAULT_INDEXING_SPEED); + this.setIndexWheelMotorVal(-DEFAULT_INDEXING_MOTOR_VALUE); } public void runIndexWheel() { - this.setIndexWheelMotorVal(DEFAULT_INDEXING_SPEED); + 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; + } + + public void reverseFlyWheel() { + this.setFlyWheelMotorVal(shooter.REVERSE_FLYWHEEL_MOTOR_VALUE); } }