Add Hall Effect Sensor code to test sensor
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheel.java
CommitLineData
cf77d84e 1
809609c9 2package org.usfirst.frc.team3501.robot.commands.shooter;
3
414d5638 4import org.usfirst.frc.team3501.robot.Robot;
ad7e6b1e 5import org.usfirst.frc.team3501.robot.subsystems.Shooter;
cf77d84e 6import org.usfirst.frc.team3501.robot.utils.PIDController;
414d5638 7
809609c9 8import edu.wpi.first.wpilibj.command.Command;
9
10/**
8c09ecc2
CZ
11 * This command runs the fly wheel at a specific speed using a PID Controller
12 * for accuracy for a given time. The fly wheel is intended to shoot balls fed
13 * by the intake wheel.
809609c9 14 *
cf77d84e 15 * @author Shaina & Chris
809609c9 16 */
17public class RunFlyWheel extends Command {
ad7e6b1e 18 private Shooter shooter = Robot.getShooter();
cf77d84e
CZ
19 private double maxTimeOut;
20
21 private PIDController wheelController;
22 private double wheelP;
23 private double wheelI;
24 private double wheelD;
25 private double target;
26
27 public RunFlyWheel(double maxTimeOut) {
ad7e6b1e 28 requires(shooter);
cf77d84e
CZ
29
30 this.wheelP = this.shooter.wheelP;
31 this.wheelI = this.shooter.wheelI;
32 this.wheelD = this.shooter.wheelD;
33 this.wheelController = new PIDController(this.wheelP, this.wheelI,
34 this.wheelD);
35 this.wheelController.setDoneRange(0.5);
36 this.wheelController.setMaxOutput(1.0);
37 this.wheelController.setMinDoneCycles(3);
38 this.target = this.shooter.CURRENT_SHOOTING_SPEED;
493a4f87 39 }
40
41 // Called just before this Command runs the first time
493a4f87 42 protected void initialize() {
cf77d84e 43 this.wheelController.setSetPoint(this.target);
493a4f87 44 }
45
46 // Called repeatedly when this Command is scheduled to run
493a4f87 47 protected void execute() {
cf77d84e 48 double shooterSpeed = this.wheelController
268b0048 49 .calcPID(this.shooter.getShooterRPM());
cf77d84e
CZ
50
51 this.shooter.setFlyWheelMotorVal(shooterSpeed);
52 }
53
54 // Make this return true when this Command no longer needs to run execute()
55 protected boolean isFinished() {
56 return timeSinceInitialized() >= maxTimeOut;
493a4f87 57 }
58
59 // Called once after isFinished returns true
493a4f87 60 protected void end() {
cf77d84e 61 this.shooter.stopFlyWheel();
493a4f87 62 }
63
64 // Called when another command which requires one or more of the same
65 // subsystems is scheduled to run
493a4f87 66 protected void interrupted() {
414d5638 67 end();
493a4f87 68 }
809609c9 69}