fix shooter commands
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheelContinuous.java
CommitLineData
809609c9 1package org.usfirst.frc.team3501.robot.commands.shooter;
2
dbec800d 3import org.usfirst.frc.team3501.robot.Robot;
00f515a1 4import org.usfirst.frc.team3501.robot.subsystems.Shooter;
cf77d84e 5import org.usfirst.frc.team3501.robot.utils.PIDController;
dbec800d 6
809609c9 7import edu.wpi.first.wpilibj.command.Command;
8
9/**
8c09ecc2
CZ
10 * This command runs the fly wheel continuously at a set speed using a PID
11 * Controller when OI button managing fly wheel is pressed. The command will run
12 * the fly wheel motor until the button triggering it is released.
b6e97560 13 *
d4507ede 14 * Should only be run from the operator interface.
15 *
973f0ac4 16 * pre-condition: This command must be run by a button in OI, with
17 * button.whileHeld(...).
357feb5c 18 *
8c09ecc2 19 * @author Shaina & Chris
809609c9 20 */
21public class RunFlyWheelContinuous extends Command {
00f515a1 22 private Shooter shooter = Robot.getShooter();
55cbd9ba 23
cf77d84e
CZ
24 private PIDController wheelController;
25 private double wheelP;
26 private double wheelI;
27 private double wheelD;
28 private double target;
e3237986 29 double shooterSpeed = 0;
cf77d84e 30
00f515a1 31 public RunFlyWheelContinuous() {
cf77d84e
CZ
32 this.wheelP = this.shooter.wheelP;
33 this.wheelI = this.shooter.wheelI;
34 this.wheelD = this.shooter.wheelD;
35 this.wheelController = new PIDController(this.wheelP, this.wheelI,
36 this.wheelD);
e3237986 37 this.wheelController.setDoneRange(10);
cf77d84e
CZ
38 this.wheelController.setMaxOutput(1.0);
39 this.wheelController.setMinDoneCycles(3);
e3237986 40 this.target = 2700;
55cbd9ba 41 }
42
7cd65a82 43 @Override
55cbd9ba 44 protected void initialize() {
cf77d84e 45 this.wheelController.setSetPoint(this.target);
55cbd9ba 46 }
47
7cd65a82 48 @Override
55cbd9ba 49 protected void execute() {
e3237986
CZ
50 double calculatedShooterIncrement = this.wheelController
51 .calcPID(this.shooter.getShooterRPM());
52 shooterSpeed += calculatedShooterIncrement;
53 if (shooterSpeed > 1.0)
54 this.shooter.setFlyWheelMotorVal(1.0);
55 else
56 this.shooter.setFlyWheelMotorVal(shooterSpeed);
57 // this.shooter.setFlyWheelMotorVal(this.shooter.CURRENT_SHOOTING_SPEED);
cf77d84e
CZ
58 }
59
7cd65a82 60 @Override
cf77d84e
CZ
61 protected boolean isFinished() {
62 return false;
55cbd9ba 63 }
64
7cd65a82 65 @Override
55cbd9ba 66 protected void end() {
cf77d84e 67 this.shooter.stopFlyWheel();
55cbd9ba 68 }
69
7cd65a82 70 @Override
55cbd9ba 71 protected void interrupted() {
135022bc 72 end();
55cbd9ba 73 }
809609c9 74}