competition fixes
[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 24 private PIDController wheelController;
cf77d84e 25
00f515a1 26 public RunFlyWheelContinuous() {
f74d236d 27 requires(shooter);
55cbd9ba 28 }
29
7cd65a82 30 @Override
55cbd9ba 31 protected void initialize() {
7ba6bc91 32 shooter.initializePIDController();
55cbd9ba 33 }
34
7cd65a82 35 @Override
55cbd9ba 36 protected void execute() {
7ba6bc91 37 shooter.setFlyWheelMotorVal(shooter.calculateShooterSpeed());
cf77d84e
CZ
38 }
39
7cd65a82 40 @Override
cf77d84e
CZ
41 protected boolean isFinished() {
42 return false;
55cbd9ba 43 }
44
7cd65a82 45 @Override
55cbd9ba 46 protected void end() {
cf77d84e 47 this.shooter.stopFlyWheel();
55cbd9ba 48 }
49
7cd65a82 50 @Override
55cbd9ba 51 protected void interrupted() {
135022bc 52 end();
55cbd9ba 53 }
809609c9 54}