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.DoubleSolenoid;
+import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
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 static final double DEFAULT_SHOOTING_SPEED = 2800; // rpm
- private static final double SHOOTING_SPEED_INCREMENT = 25;
+ private PIDController wheelController;
- private double currentShootingSpeed = DEFAULT_SHOOTING_SPEED;
+ private static final double RPM_THRESHOLD = 10;
+ private static final double DEFAULT_INDEXING_MOTOR_VALUE = -0.75;
+ private static final double DEFAULT_SHOOTING_SPEED = 3100; // rpm
+ private static final double SHOOTING_SPEED_INCREMENT = 50;
+ private static final int ACCEPTABLE_SHOOTING_DEVIATION = 300;
+
+ private double targetShootingSpeed = DEFAULT_SHOOTING_SPEED;
+ private double currentShooterMotorValue = 0;
+
+ private final DoubleSolenoid piston;
private Shooter() {
flyWheel1 = new CANTalon(Constants.Shooter.FLY_WHEEL1);
indexWheel = new CANTalon(Constants.Shooter.INDEX_WHEEL);
hallEffect = new HallEffectSensor(Constants.Shooter.HALL_EFFECT_PORT, 1);
+
+ piston = new DoubleSolenoid(Constants.Shooter.MODULE_NUMBER,
+ Constants.Shooter.PISTON_FORWARD, Constants.Shooter.PISTON_REVERSE);
}
/**
}
+ 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 Value getPistonValue() {
+ return piston.get();
+ }
+
+ public void setHighGear() {
+ changeGear(Constants.Shooter.HIGH_GEAR);
+ }
+
+ public void setLowGear() {
+ changeGear(Constants.Shooter.LOW_GEAR);
+ }
+
+ private void changeGear(DoubleSolenoid.Value gear) {
+ piston.set(gear);
+ }
+
+ public boolean isShooterRPMAtTargetSpeed() {
+ return isShooterRPMWithinRangeOfTargetSpeed(ACCEPTABLE_SHOOTING_DEVIATION);
+ }
+
+ public boolean isShooterRPMWithinRangeOfTargetSpeed(int acceptableRPMError) {
+ double shooterSpeed = getShooterRPM();
+ if (shooterSpeed > DEFAULT_SHOOTING_SPEED - acceptableRPMError
+ && shooterSpeed < DEFAULT_SHOOTING_SPEED + acceptableRPMError) {
+ return true;
+ }
+ return false;
}
}