c5101fc7d0dea5e23353b3a6c6b890ad35247450
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / commands / shooter / RunFlyWheel.java
1
2 package org.usfirst.frc.team3501.robot.commands.shooter;
3
4 import org.usfirst.frc.team3501.robot.Robot;
5 import org.usfirst.frc.team3501.robot.subsystems.Shooter;
6 import org.usfirst.frc.team3501.robot.utils.PIDController;
7
8 import edu.wpi.first.wpilibj.command.Command;
9
10 /**
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.
14 *
15 * @author Shaina & Chris
16 */
17 public class RunFlyWheel extends Command {
18 private Shooter shooter = Robot.getShooter();
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 private double shooterSpeed = 0;
27
28 public RunFlyWheel(double maxTimeOut) {
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.getCurrentShootingSpeed();
39 }
40
41 // Called just before this Command runs the first time
42 @Override
43 protected void initialize() {
44 this.wheelController.setSetPoint(this.target);
45 }
46
47 // Called repeatedly when this Command is scheduled to run
48 @Override
49 protected void execute() {
50 double calculatedShooterIncrement = this.wheelController
51 .calcPID(this.shooter.getShooterRPM());
52 shooterSpeed += calculatedShooterIncrement;
53 this.shooter.setFlyWheelMotorVal(shooterSpeed);
54 }
55
56 // Make this return true when this Command no longer needs to run execute()
57 @Override
58 protected boolean isFinished() {
59 return timeSinceInitialized() >= maxTimeOut;
60 }
61
62 // Called once after isFinished returns true
63 @Override
64 protected void end() {
65 this.shooter.stopFlyWheel();
66 }
67
68 // Called when another command which requires one or more of the same
69 // subsystems is scheduled to run
70 @Override
71 protected void interrupted() {
72 }
73 }