From 90b435ced654236fa5b553809969104b1b2f62f5 Mon Sep 17 00:00:00 2001 From: Eric Sandoval Date: Sat, 4 Feb 2017 15:17:24 -0800 Subject: [PATCH] add seperate pid controllers --- src/org/usfirst/frc/team3501/robot/Robot.java | 21 ++++++++++--------- .../robot/commands/driving/TurnForAngle.java | 2 +- .../team3501/robot/subsystems/DriveTrain.java | 4 ++++ 3 files changed, 16 insertions(+), 11 deletions(-) diff --git a/src/org/usfirst/frc/team3501/robot/Robot.java b/src/org/usfirst/frc/team3501/robot/Robot.java index eadb9aa..c24279b 100644 --- a/src/org/usfirst/frc/team3501/robot/Robot.java +++ b/src/org/usfirst/frc/team3501/robot/Robot.java @@ -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(); } 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 7e07577..5d85471 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -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); } diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index 5a4d4b7..f967217 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -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(); -- 2.30.2