X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fdriving%2FTurnForAngle.java;h=86176f15fe9e3b03ebaf0ac447af00f597f1cb17;hp=334fa0b67d278ad2dd38afe3be68d54fd6487b09;hb=f0a71840f17c1039ce4be1f66cf324cc979a9966;hpb=8e4c083cf74939e98aabaf8aaf45976a148d0666 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 334fa0b..86176f1 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -1,7 +1,10 @@ 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; @@ -9,41 +12,75 @@ 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 - * motorVal: the motor input to set the motors to + * 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(double angle, Direction direction, double motorVal) { + 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, double maxTimeOut) { requires(Robot.getDriveTrain()); + this.direction = direction; + this.maxTimeOut = maxTimeOut; + this.target = angle; + + this.gyroP = driveTrain.defaultGyroP; + this.gyroI = driveTrain.defaultGyroI; + this.gyroD = driveTrain.defaultGyroD; + + 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.driveTrain.resetGyro(); + this.gyroController.setSetPoint(this.target); } - // Called repeatedly when this Command is scheduled to run @Override protected void execute() { + double xVal = 0; + + xVal = this.gyroController + .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle()); + + double leftDrive; + double rightDrive; + if (direction == Constants.Direction.RIGHT) { + leftDrive = xVal; + rightDrive = -xVal; + } else { + 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(); } }