X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fdriving%2FTurnForAngle.java;h=b95c8223a69fccad10d0f3d3cc2bc882129bb6ed;hb=b70398a7d5ac5f4ce64156d84227ccb4828c0615;hp=becaa3a2b759b4289abdf36b675b2f621c1f9127;hpb=9b9d6bed9e6e6d0ef16d34d692bc93d3ae9be197;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 becaa3a..b95c822 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -1,49 +1,94 @@ 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.Relay.Direction; 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 - * + * 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(); + + Direction direction; + private double maxTimeOut; + private PIDController gyroController; + + private double target; + private double gyroP; + private double gyroI; + private double gyroD; - public TurnForAngle(double angle, Direction direction) { + private double zeroAngle; + + public TurnForAngle(double angle, Direction direction, double maxTimeOut) { requires(Robot.getDriveTrain()); + this.direction = direction; + this.maxTimeOut = maxTimeOut; + this.target = Math.abs(angle); + + if (angle > 90) { + this.gyroP = driveTrain.largeTurnP; + this.gyroI = driveTrain.largeTurnI; + this.gyroD = driveTrain.largeTurnD; + } else { + this.gyroP = driveTrain.smallTurnP; + this.gyroI = driveTrain.smallTurnI; + this.gyroD = driveTrain.smallTurnD; + } + + this.gyroController = new PIDController(this.gyroP, this.gyroI, this.gyroD); + this.gyroController.setDoneRange(1); + this.gyroController.setMinDoneCycles(5); } - // Called just before this Command runs the first time @Override protected void initialize() { + this.driveTrain.resetEncoders(); + this.gyroController.setSetPoint(this.target); + this.zeroAngle = driveTrain.getAngle(); } - // Called repeatedly when this Command is scheduled to run @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); } - // Make this return true when this Command no longer needs to run execute() @Override protected boolean isFinished() { - return false; + return timeSinceInitialized() >= maxTimeOut || gyroController.isDone(); } - // Called once after isFinished returns true @Override protected void end() { } - // Called when another command which requires one or more of the same - // subsystems is scheduled to run @Override protected void interrupted() { + end(); } }