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=d3ed4499eefce8b42ea56893f566c8ee36a6642c 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 f6e11f4..bd923a2 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java @@ -27,9 +27,10 @@ public class DriveDistance extends Command { public DriveDistance(double distance, double maxTimeOut) { requires(driveTrain); this.target = distance; + this.driveController = driveTrain.getDriveController(); this.driveController.setDoneRange(0.5); - this.driveController.setMaxOutput(motorVal); + this.driveController.setMaxOutput(1.1); this.driveController.setMinDoneCycles(5); } diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index aae3d8f..633b12b 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -14,7 +14,6 @@ import edu.wpi.first.wpilibj.RobotDrive; import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { - public static double driveP, driveI, driveD; public static double turnP, turnI, turnD; @@ -56,17 +55,12 @@ public class DriveTrain extends Subsystem { private PIDController gyroController; private boolean isClimbing; - private static double CLIMBER_SPEED;; - public boolean shouldBeClimbing = false; - - private PIDController driveController; - private PIDController gyroController; private DriveTrain() { // PID TUNING driveController = new PIDController(driveP, driveI, driveD); - gyroController = new PIDController(turnP, turnI, turnD + gyroController = new PIDController(turnP, turnI, turnD); // MOTOR CONTROLLERS frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);