+
package org.usfirst.frc.team3501.robot.commands.shooter;
import org.usfirst.frc.team3501.robot.Robot;
import org.usfirst.frc.team3501.robot.subsystems.Shooter;
+import org.usfirst.frc.team3501.robot.utils.PIDController;
-import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.command.Command;
/**
- * This command runs the fly wheel at a given speed for a given time. The fly
- * wheel is intended to shoot balls fed by the intake wheel.
+ * This command runs the fly wheel at a specific speed using a PID Controller
+ * for accuracy for a given time. The fly wheel is intended to shoot balls fed
+ * by the intake wheel.
*
- * @author Shaina
+ * @author Shaina & Chris
*/
public class RunFlyWheel extends Command {
private Shooter shooter = Robot.getShooter();
- Timer timer;
- private double time;
+ private double maxTimeOut;
+
+ private PIDController wheelController;
+ private double wheelP;
+ private double wheelI;
+ private double wheelD;
+ private double target;
- /**
- * See JavaDoc comment in class for details
- *
- * @param motorVal
- * value range from -1 to 1
- * @param time
- * in seconds, amount of time to run fly wheel motor
- */
- public RunFlyWheel(double time) {
- requires(shooter);
+ public RunFlyWheel(double maxTimeOut) {
- timer = new Timer();
- this.time = time;
+ this.wheelP = this.shooter.wheelP;
+ this.wheelI = this.shooter.wheelI;
+ this.wheelD = this.shooter.wheelD;
+ this.wheelController = new PIDController(this.wheelP, this.wheelI,
+ this.wheelD);
+ this.wheelController.setDoneRange(0.5);
+ this.wheelController.setMaxOutput(1.0);
+ this.wheelController.setMinDoneCycles(3);
+ this.target = this.shooter.getCurrentShootingSpeed();
}
// Called just before this Command runs the first time
@Override
protected void initialize() {
- timer.start();
- shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED);
+ this.wheelController.setSetPoint(this.target);
}
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
+ double shooterSpeed = this.wheelController
+ .calcPID(this.shooter.getShooterRPM());
+
+ this.shooter.setFlyWheelMotorVal(shooterSpeed);
+ }
+
+ // Make this return true when this Command no longer needs to run execute()
+ @Override
+ protected boolean isFinished() {
+ return timeSinceInitialized() >= maxTimeOut;
}
// Called once after isFinished returns true
@Override
protected void end() {
- shooter.stopFlyWheel();
+ this.shooter.stopFlyWheel();
}
// Called when another command which requires one or more of the same
// subsystems is scheduled to run
@Override
protected void interrupted() {
- end();
- }
-
- @Override
- protected boolean isFinished() {
- return timer.get() >= time;
}
-
}