add seperate pid controllers
authorEric Sandoval <harpnart@gmail.com>
Sat, 4 Feb 2017 23:17:24 +0000 (15:17 -0800)
committerEric Sandoval <harpnart@gmail.com>
Sun, 19 Feb 2017 18:38:33 +0000 (10:38 -0800)
src/org/usfirst/frc/team3501/robot/Robot.java
src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java
src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java

index eadb9aaefc9343367ee1695726feceac780e5326..c24279b89f118250c73a71dad42ab22bfdf8f22f 100644 (file)
@@ -56,23 +56,24 @@ public class Robot extends IterativeRobot {
   public void autonomousPeriodic() {
     Scheduler.getInstance().run();
 
-    double DriveP = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val,
+    double driveP = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val,
         Constants.DriveTrain.PID_ERROR);
-    double DriveI = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_I_Val,
+    double driveI = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_I_Val,
         Constants.DriveTrain.PID_ERROR);
-    double DriveD = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val,
+    double driveD = SmartDashboard.getNumber(Constants.DriveTrain.DRIVE_D_Val,
         Constants.DriveTrain.PID_ERROR);
-
-    double GyroP = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_P_Val,
+    double gyroP = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_P_Val,
         Constants.DriveTrain.PID_ERROR);
-    double GyroI = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_I_Val,
+    double gyroI = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_I_Val,
         Constants.DriveTrain.PID_ERROR);
-    double GyroD = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_D_Val,
-
+    double gyroD = SmartDashboard.getNumber(Constants.DriveTrain.GYRO_D_Val,
         Constants.DriveTrain.PID_ERROR);
 
-    DriveTrain.getDriveTrain().getDriveController().setConstants(DriveP, DriveI,
-        DriveD);
+    DriveTrain.getDriveTrain().getDriveController().setConstants(driveP, driveI,
+        driveD);
+
+    DriveTrain.getDriveTrain().getGyroController().setConstants(driveP, driveI,
+        driveD);
 
     // new DriveDistance(SETPOINT, SPEED).start();
   }
index 7e07577b7b001b9d767b89325320670bec1ec212..5d85471e55b4d97ca046804eb75be0c98c0b1377 100755 (executable)
@@ -40,7 +40,7 @@ public class TurnForAngle extends Command {
     this.gyroI = driveTrain.turnI;
     this.gyroD = driveTrain.turnD;
 
-    this.gyroController = Robot.getDriveTrain().getDriveController();
+    this.gyroController = Robot.getDriveTrain().getGyroController();
     this.gyroController.setDoneRange(1);
     this.gyroController.setMinDoneCycles(5);
   }
index 5a4d4b786e200ef7984e6ab121d92a8f59e2548f..f967217d5f6ae651e7b76777211bb5dbc5199117 100644 (file)
@@ -79,6 +79,10 @@ public class DriveTrain extends Subsystem {
     return this.driveController;
   }
 
+  public PIDController getGyroController() {
+    return this.gyroController;
+  }
+
   public static DriveTrain getDriveTrain() {
     if (driveTrain == null) {
       driveTrain = new DriveTrain();