From: EvanYap Date: Sat, 4 Feb 2017 23:25:54 +0000 (-0800) Subject: fix alot of unnecessary/not used code and init gyroController X-Git-Url: http://challenge-bot.com/repos/?p=3501%2F2017steamworks;a=commitdiff_plain;h=4288a3a410e17add73185fe31fa53b3929ac2bf5 fix alot of unnecessary/not used code and init gyroController --- 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 d78ab4b..ccbe5fd 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java @@ -28,12 +28,6 @@ public class DriveDistance extends Command { requires(driveTrain); this.maxTimeOut = maxTimeOut; this.target = distance; - - this.driveP = driveTrain.driveP; - this.driveI = driveTrain.driveI; - this.driveD = driveTrain.driveD; - this.gyroP = driveTrain.driveStraightGyroP; - this.driveController = driveTrain.getDriveController(); this.driveController.setDoneRange(0.5); this.driveController.setMaxOutput(1.0); 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 add9556..83788d7 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -32,6 +32,10 @@ public class TurnForAngle extends Command { this.direction = direction; this.maxTimeOut = maxTimeOut; this.target = Math.abs(angle); +<<<<<<< HEAD +======= + this.zeroAngle = driveTrain.getAngle(); +>>>>>>> fix alot of unnecessary/not used code and init gyroController this.gyroController = Robot.getDriveTrain().getGyroController(); this.gyroController.setDoneRange(1); diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 847419a..dbe14ac 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -16,7 +16,6 @@ import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { public static double driveP, driveI, driveD; - public static double turnP, turnI, turnD; public static double driveStraightGyroP = 0.01;