X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fshooter%2FRunFlyWheel.java;h=d68b13eca0b71d3cc3024769ac8f56777da1cbbe;hp=6ac5d69f3e1934c557adde63add9c5a72d4c5982;hb=cf77d84e212b20171a5a3397b26fe7f98f4ba460;hpb=381dad77be9ae65d463812e2c2ad852363084219 diff --git a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java index 6ac5d69..d68b13e 100644 --- a/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java +++ b/src/org/usfirst/frc/team3501/robot/commands/shooter/RunFlyWheel.java @@ -1,7 +1,9 @@ + 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; @@ -9,52 +11,58 @@ 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. * - * @author Shaina + * @author Shaina & Chris */ public class RunFlyWheel extends Command { private Shooter shooter = Robot.getShooter(); - private double time; - - /** - * 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) { + private double maxTimeOut; + + private PIDController wheelController; + private double wheelP; + private double wheelI; + private double wheelD; + private double target; + + public RunFlyWheel(double maxTimeOut) { requires(shooter); - 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.CURRENT_SHOOTING_SPEED; } // Called just before this Command runs the first time - @Override protected void initialize() { + this.wheelController.setSetPoint(this.target); } // Called repeatedly when this Command is scheduled to run - @Override protected void execute() { - shooter.setFlyWheelMotorVal(shooter.CURRENT_SHOOTING_SPEED); + double shooterSpeed = this.wheelController + .calcPID(this.shooter.getShooterSpeed()); + + this.shooter.setFlyWheelMotorVal(shooterSpeed); + } + + // Make this return true when this Command no longer needs to run execute() + 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 timeSinceInitialized() >= time; - } - }