X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fdriving%2FTurnForAngle.java;h=44434c694531aa65751e95f307fe740ffbf1378a;hb=refs%2Fheads%2Fchris%2FautonGearStrategy;hp=06d14f6c4a1ba407dafb081655f5cba7e2b3545b;hpb=aa160dfd8f61661dad049ff753e8547faae79b5c;p=3501%2F2017steamworks diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java index 06d14f6..44434c6 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -1,42 +1,89 @@ package org.usfirst.frc.team3501.robot.commands.driving; +import org.usfirst.frc.team3501.robot.Constants; +import org.usfirst.frc.team3501.robot.Constants.Direction; import org.usfirst.frc.team3501.robot.Robot; +import org.usfirst.frc.team3501.robot.subsystems.DriveTrain; +import org.usfirst.frc.team3501.robot.utils.PIDController; import edu.wpi.first.wpilibj.command.Command; /** + * This command turns the robot for a specified angle in specified direction - + * either left or right * + * parameters: angle: the robot will turn - in degrees direction: the robot will + * turn - either right or left maxTimeOut: the max time this command will be + * allowed to run on for */ public class TurnForAngle extends Command { + private DriveTrain driveTrain = Robot.getDriveTrain(); - public TurnForAngle() { - requires(Robot.getDriveTrain()); - } + Direction direction; + private double maxTimeOut; + private PIDController gyroController; - // Called just before this Command runs the first time - @Override - protected void initialize() { - } + private double target; + private double gyroP; + private double gyroI; + private double gyroD; - // Called repeatedly when this Command is scheduled to run - @Override - protected void execute() { - } + private double zeroAngle; - // Make this return true when this Command no longer needs to run execute() - @Override - protected boolean isFinished() { - return false; - } + public TurnForAngle(double angle, Direction direction, double maxTimeOut) { + requires(Robot.getDriveTrain()); + this.direction = direction; + this.maxTimeOut = maxTimeOut; + this.target = Math.abs(angle); - // Called once after isFinished returns true - @Override - protected void end() { - } + this.gyroP = driveTrain.turnP; + this.gyroI = driveTrain.turnI; + this.gyroD = driveTrain.turnD; + + this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD); + this.gyroController.setDoneRange(1); + this.gyroController.setMinDoneCycles(5); + } + + @Override + protected void initialize() { + this.driveTrain.resetEncoders(); + this.gyroController.setSetPoint(this.target); + this.zeroAngle = driveTrain.getAngle(); + } - // Called when another command which requires one or more of the same - // subsystems is scheduled to run - @Override - protected void interrupted() { + @Override + protected void execute() { + double xVal = 0; + + xVal = this.gyroController + .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle)); + + double leftDrive = 0; + double rightDrive = 0; + if (direction == Constants.Direction.RIGHT) { + leftDrive = xVal; + rightDrive = -xVal; + } else if (direction == Constants.Direction.LEFT) { + leftDrive = -xVal; + rightDrive = xVal; } + + this.driveTrain.setMotorValues(leftDrive, rightDrive); + System.out.println(this.driveTrain.getAngle() - this.zeroAngle); + } + + @Override + protected boolean isFinished() { + return timeSinceInitialized() >= maxTimeOut || gyroController.isDone(); + } + + @Override + protected void end() { + } + + @Override + protected void interrupted() { + end(); + } }