fix alot of unnecessary/not used code and init gyroController
authorEvanYap <evanyap.14@gmail.com>
Sat, 4 Feb 2017 23:25:54 +0000 (15:25 -0800)
committerEric Sandoval <harpnart@gmail.com>
Sun, 19 Feb 2017 18:44:51 +0000 (10:44 -0800)
src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java

index f6e11f4c94268c7190d540edb3045e618f2e5488..bd923a2af73427ffa69ad842431c1736feb4a12e 100755 (executable)
@@ -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);
   }
 
index aae3d8fe7d7e9f9a2fb332d5bb500c5a896541fd..633b12b4f78298ff07c348f08837ccf55010b9a7 100644 (file)
@@ -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);