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:38:39 +0000 (10:38 -0800)
src/org/usfirst/frc/team3501/robot/Robot.java
src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java
src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java

index cde55dc61d13cf2c33e969d72b2d510d2803e2a5..039f5d65a78a0becbf3672e4417b10e20331985b 100644 (file)
@@ -62,6 +62,7 @@ public class Robot extends IterativeRobot {
         Constants.DriveTrain.PID_ERROR);
     double driveD = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val,
         Constants.DriveTrain.PID_ERROR);
+
     double gyroP = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_P_Val,
         Constants.DriveTrain.PID_ERROR);
     double gyroI = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_I_Val,
@@ -72,15 +73,12 @@ public class Robot extends IterativeRobot {
     DriveTrain.getDriveTrain().getDriveController().setConstants(driveP, driveI,
         driveD);
 
-    DriveTrain.getDriveTrain().getGyroController().setConstants(driveP, driveI,
-        driveD);
+    DriveTrain.getDriveTrain().getGyroController().setConstants(gyroP, gyroI,
+        gyroD);
 
     // new DriveDistance(SETPOINT, SPEED).start();
-    double Setpoint = SmartDashboard.getNumber(
-        Constants.DriveTrain.DRIVE_TARGET_DIST, Constants.DriveTrain.PID_ERROR);
-    double Speed = SmartDashboard.getNumber(
-        Constants.DriveTrain.DRIVE_MOTOR_VAL, Constants.DriveTrain.PID_ERROR);
 
+    // new TurnForAngle(0, Direction.FORWARD, 5).start();
   }
 
   @Override
index ba7921e1f38d11bae650ebd9cf2d52dd54465296..98628f34c9df8260dafcaab43d51dd05aa1d7508 100755 (executable)
@@ -22,9 +22,6 @@ public class DriveDistance extends Command {
   private Preferences prefs;
   private PIDController driveController;
 
-  private double driveP;
-  private double driveI;
-  private double driveD;
   private double gyroP;
 
   public DriveDistance(double distance, double maxTimeOut) {
@@ -32,10 +29,6 @@ public class DriveDistance extends Command {
     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);
index 5d85471e55b4d97ca046804eb75be0c98c0b1377..add95564848a6857e5df98c002992a610d619572 100755 (executable)
@@ -24,9 +24,6 @@ public class TurnForAngle extends Command {
   private PIDController gyroController;
 
   private double target;
-  private double gyroP;
-  private double gyroI;
-  private double gyroD;
 
   private double zeroAngle;
 
@@ -36,10 +33,6 @@ public class TurnForAngle extends Command {
     this.maxTimeOut = maxTimeOut;
     this.target = Math.abs(angle);
 
-    this.gyroP = driveTrain.turnP;
-    this.gyroI = driveTrain.turnI;
-    this.gyroD = driveTrain.turnD;
-
     this.gyroController = Robot.getDriveTrain().getGyroController();
     this.gyroController.setDoneRange(1);
     this.gyroController.setMinDoneCycles(5);
index f967217d5f6ae651e7b76777211bb5dbc5199117..bb7ef453b1e2944ebdfec1aa953a12d7f3247c00 100644 (file)
@@ -16,7 +16,7 @@ import edu.wpi.first.wpilibj.command.Subsystem;
 public class DriveTrain extends Subsystem {
 
   public static double driveP, driveI, driveD;
-  public static double turnP = 0.004, turnI = 0.0013, turnD = -0.005;
+  public static double turnP, turnI, turnD;
   public static double driveStraightGyroP = 0.01;
 
   public static final double WHEEL_DIAMETER = 6; // inches
@@ -45,6 +45,7 @@ public class DriveTrain extends Subsystem {
   private DriveTrain() {
 
     driveController = new PIDController(driveP, driveI, driveD);
+    gyroController = new PIDController(turnP, turnI, turnD);
 
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);