X-Git-Url: http://challenge-bot.com/repos/?a=blobdiff_plain;f=src%2Forg%2Fusfirst%2Ffrc%2Fteam3501%2Frobot%2Fcommands%2Fdriving%2FDriveDistance.java;h=7b721e0a46dd1a6bba47e1cdf9dda7e9447e6e08;hb=9ca89e45fa84b2ec93bc6adf60c7dde1e0a7defb;hp=5c0c20b92a7ee20f2a83d0fbaec3da6792462aba;hpb=8e4c083cf74939e98aabaf8aaf45976a148d0666;p=3501%2F2017steamworks diff --git a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java index 5c0c20b..7b721e0 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java @@ -17,18 +17,15 @@ import edu.wpi.first.wpilibj.command.Command; public class DriveDistance extends Command { private DriveTrain driveTrain = Robot.getDriveTrain(); private double maxTimeOut; - private PIDController driveController; - private PIDController gyroController; - private Preferences prefs; - private double target; - private double gyroP; - private double gyroI; - private double gyroD; + private double zeroAngle; + private Preferences prefs; + private PIDController driveController; private double driveP; private double driveI; private double driveD; + private double gyroP; public DriveDistance(double distance, double maxTimeOut) { requires(driveTrain); @@ -38,59 +35,38 @@ public class DriveDistance extends Command { this.driveP = driveTrain.driveP; this.driveI = driveTrain.driveI; this.driveD = driveTrain.driveD; - this.gyroP = driveTrain.defaultGyroP; - this.gyroI = driveTrain.defaultGyroI; - this.gyroD = driveTrain.defaultGyroD; - this.driveController = new PIDController(this.driveP, this.driveI, - this.driveD); - this.driveController.setDoneRange(0.5); + this.gyroP = driveTrain.driveStraightGyroP; + this.driveController = new PIDController(driveP, driveI, driveD); + this.driveController.setDoneRange(1.0); this.driveController.setMaxOutput(1.0); this.driveController.setMinDoneCycles(5); - - 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.driveTrain.resetGyro(); this.driveController.setSetPoint(this.target); - this.gyroController.setSetPoint(this.driveTrain.getZeroAngle()); + this.zeroAngle = driveTrain.getAngle(); } @Override protected void execute() { - double xVal = 0; - double yVal = this.driveController - .calcPID(this.driveTrain.getAvgEncoderDistance()); + double xVal = gyroP * (driveTrain.getAngle() - zeroAngle); + double yVal = driveController.calcPID(driveTrain.getRightEncoderDistance()); - if (this.driveTrain.getAngle() - this.driveTrain.getZeroAngle() < 30) { - xVal = -this.gyroController - .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle()); - } - // System.out.println("turn: " + xVal); double leftDrive = yVal - xVal; double rightDrive = yVal + xVal; - this.driveTrain.setMotorValues(leftDrive, rightDrive); - - driveTrain.printEncoderOutput(); - // System.out.println("motorval: " + yVal); } @Override protected boolean isFinished() { - boolean isDone = this.driveController.isDone(); - if (timeSinceInitialized() >= maxTimeOut || isDone) - System.out.println("time: " + timeSinceInitialized()); - return timeSinceInitialized() >= maxTimeOut || isDone; + return timeSinceInitialized() >= maxTimeOut + || this.driveController.isDone(); } @Override protected void end() { - driveTrain.stop(); } @Override