X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fshooter%2FRunFlyWheelContinuous.java;h=047fad40885a8e2f5caad590004cab64493dc5bb;hb=e32379867a61eb104544b90d917b7ab48d704e25;hp=a5e8501f1a5b50b137221d1b8fd4d44827e52ee2;hpb=dbec800dc8d5a7131e729e7f1c07023798813cbf;p=3501%2F2017steamworks diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java index a5e8501..047fad4 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheelContinuous.java @@ -1,59 +1,74 @@ 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.command.Command; /** - * This command will run the fly wheel motor continuously until the button - * triggering it is released. + * This command runs the fly wheel continuously at a set speed using a PID + * Controller when OI button managing fly wheel is pressed. The command will run + * the fly wheel motor until the button triggering it is released. + * + * Should only be run from the operator interface. * * pre-condition: This command must be run by a button in OI, with * button.whileHeld(...). * - * @author Shaina + * @author Shaina & Chris */ public class RunFlyWheelContinuous extends Command { - private double motorVal; - - /** - * See JavaDoc comment in class for details - * - * @param motorVal - * value range from -1 to 1 - */ - public RunFlyWheelContinuous(double motorVal) { - this.motorVal = motorVal; + private Shooter shooter = Robot.getShooter(); + + private PIDController wheelController; + private double wheelP; + private double wheelI; + private double wheelD; + private double target; + double shooterSpeed = 0; + + public RunFlyWheelContinuous() { + 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(10); + this.wheelController.setMaxOutput(1.0); + this.wheelController.setMinDoneCycles(3); + this.target = 2700; } - // Called just before this Command runs the first time @Override protected void initialize() { - Robot.getShooter().setFlyWheelMotorVal(motorVal); + this.wheelController.setSetPoint(this.target); } - // Called repeatedly when this Command is scheduled to run @Override protected void execute() { + double calculatedShooterIncrement = this.wheelController + .calcPID(this.shooter.getShooterRPM()); + shooterSpeed += calculatedShooterIncrement; + if (shooterSpeed > 1.0) + this.shooter.setFlyWheelMotorVal(1.0); + else + this.shooter.setFlyWheelMotorVal(shooterSpeed); + // this.shooter.setFlyWheelMotorVal(this.shooter.CURRENT_SHOOTING_SPEED); } - // Called once after isFinished returns true @Override - protected void end() { - Robot.getShooter().stopFlyWheel(); + protected boolean isFinished() { + return false; } - // Called when another command which requires one or more of the same - // subsystems is scheduled to run @Override - protected void interrupted() { - end(); + protected void end() { + this.shooter.stopFlyWheel(); } @Override - protected boolean isFinished() { - return false; - + protected void interrupted() { + end(); } - }