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=542234fe5ed6a80a8ce95565150d1af60f41621d fix alot of unnecessary/not used code and init gyroController --- diff --git a/src/org/usfirst/frc/team3501/robot/Robot.java b/src/org/usfirst/frc/team3501/robot/Robot.java index cde55dc..039f5d6 100644 --- a/src/org/usfirst/frc/team3501/robot/Robot.java +++ b/src/org/usfirst/frc/team3501/robot/Robot.java @@ -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 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 ba7921e..98628f3 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/DriveDistance.java @@ -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); 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 5d85471..add9556 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -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); diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index f967217..bb7ef45 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -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);