From 571fb5c99d2323fed344b332f687597cd53d4d31 Mon Sep 17 00:00:00 2001 From: Cindy Zhang Date: Tue, 31 Jan 2017 20:06:09 -0800 Subject: [PATCH] fix bugs for TurnForAngle and tune constants --- .../robot/commands/driving/TurnForAngle.java | 14 ++++++++------ .../frc/team3501/robot/subsystems/DriveTrain.java | 8 ++++---- .../frc/team3501/robot/utils/PIDController.java | 1 - 3 files changed, 12 insertions(+), 11 deletions(-) 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 86176f1..f9f5c7f 100755 --- a/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java +++ b/src/org/usfirst/frc/team3501/robot/commands/driving/TurnForAngle.java @@ -28,11 +28,14 @@ public class TurnForAngle extends Command { private double gyroI; private double gyroD; + private double zeroAngle; + public TurnForAngle(double angle, Direction direction, double maxTimeOut) { requires(Robot.getDriveTrain()); this.direction = direction; this.maxTimeOut = maxTimeOut; - this.target = angle; + this.target = Math.abs(angle); + this.zeroAngle = driveTrain.getAngle(); this.gyroP = driveTrain.defaultGyroP; this.gyroI = driveTrain.defaultGyroI; @@ -46,7 +49,6 @@ public class TurnForAngle extends Command { @Override protected void initialize() { this.driveTrain.resetEncoders(); - this.driveTrain.resetGyro(); this.gyroController.setSetPoint(this.target); } @@ -55,14 +57,14 @@ public class TurnForAngle extends Command { double xVal = 0; xVal = this.gyroController - .calcPID(this.driveTrain.getAngle() - this.driveTrain.getZeroAngle()); + .calcPID(Math.abs(this.driveTrain.getAngle() - this.zeroAngle)); - double leftDrive; - double rightDrive; + double leftDrive = 0; + double rightDrive = 0; if (direction == Constants.Direction.RIGHT) { leftDrive = xVal; rightDrive = -xVal; - } else { + } else if (direction == Constants.Direction.LEFT) { leftDrive = -xVal; rightDrive = xVal; } diff --git a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java index eb9a442..1ba8c8c 100644 --- a/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java +++ b/src/org/usfirst/frc/team3501/robot/subsystems/DriveTrain.java @@ -11,9 +11,9 @@ import edu.wpi.first.wpilibj.RobotDrive; import edu.wpi.first.wpilibj.command.Subsystem; public class DriveTrain extends Subsystem { - public static double driveP = 0.008, driveI = 0.001, driveD = -0.002; - public static double defaultGyroP = 0.006, defaultGyroI = 0.00000, - defaultGyroD = -0.000; + public static double driveP = 0.006, driveI = 0.001, driveD = -0.002; + public static double defaultGyroP = 0.004, defaultGyroI = 0.0013, + defaultGyroD = -0.005; private double gyroZero = 0; public static final double WHEEL_DIAMETER = 6; // inches @@ -125,7 +125,7 @@ public class DriveTrain extends Subsystem { } public void resetGyro() { - this.gyroZero = this.getAngle(); + this.imu.reset(); } public double getZeroAngle() { diff --git a/src/org/usfirst/frc/team3501/robot/utils/PIDController.java b/src/org/usfirst/frc/team3501/robot/utils/PIDController.java index b8ec465..c6ab0fb 100644 --- a/src/org/usfirst/frc/team3501/robot/utils/PIDController.java +++ b/src/org/usfirst/frc/team3501/robot/utils/PIDController.java @@ -161,7 +161,6 @@ public class PIDController { // close enough to target if (currError <= this.doneRange) { this.doneCycleCount++; - System.out.println(doneCycleCount); } // not close enough to target else { -- 2.30.2