finish implement driveDistance and TurnForAngle using PID algorithm
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 364340e106f2901ab65720f71d0f402df0aa950d..c445f630109f1d4d30067f6735fb65e8c5a6395c 100644 (file)
@@ -2,14 +2,21 @@ package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
+import org.usfirst.frc.team3501.robot.utils.BNO055;
 
 import com.ctre.CANTalon;
 
 import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.I2C.Port;
 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;
+  private double gyroZero = 0;
+
   public static final double WHEEL_DIAMETER = 6; // inches
   public static final int ENCODER_PULSES_PER_REVOLUTION = 256;
   public static final double INCHES_PER_PULSE = WHEEL_DIAMETER * Math.PI
@@ -20,6 +27,8 @@ public class DriveTrain extends Subsystem {
   private final RobotDrive robotDrive;
   private final Encoder leftEncoder, rightEncoder;
 
+  private BNO055 imu;
+
   private DriveTrain() {
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -38,6 +47,10 @@ public class DriveTrain extends Subsystem {
 
     // ROBOT DRIVE
     robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
+
+    this.imu = BNO055.getInstance(BNO055.opmode_t.OPERATION_MODE_IMUPLUS,
+        BNO055.vector_type_t.VECTOR_EULER, Port.kOnboard, (byte) 0x28);
+    gyroZero = imu.getHeading();
   }
 
   public static DriveTrain getDriveTrain() {
@@ -64,20 +77,12 @@ public class DriveTrain extends Subsystem {
     setMotorValues(0, 0);
   }
 
-  public double getFrontLeftMotorVal() {
-    return frontLeft.get();
-  }
-
-  public double getFrontRightMotorVal() {
-    return frontRight.get();
-  }
-
-  public double getRearLeftMotorVal() {
-    return frontLeft.get();
+  public double getLeftMotorVal() {
+    return (frontLeft.get() + rearLeft.get()) / 2;
   }
 
-  public double getRearRightMotorVal() {
-    return frontLeft.get();
+  public double getRightMotorVal() {
+    return (frontRight.get() + rearRight.get()) / 2;
   }
 
   // ENCODER METHODS
@@ -90,6 +95,12 @@ public class DriveTrain extends Subsystem {
     return rightEncoder.getDistance();
   }
 
+  public void printEncoderOutput() {
+    // System.out.println("left: " + getLeftEncoderDistance());
+    // System.out.println("right: " + getRightEncoderDistance());
+    System.out.println(getAvgEncoderDistance());
+  }
+
   public double getAvgEncoderDistance() {
     return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
   }
@@ -111,6 +122,22 @@ public class DriveTrain extends Subsystem {
     return (getLeftSpeed() + getRightSpeed()) / 2.0;
   }
 
+  // ------Gyro------//
+  public double getAngle() {
+    if (!this.imu.isInitialized())
+      return -1;
+    return this.imu.getHeading() - this.gyroZero;
+  }
+
+  public void resetGyro() {
+    this.gyroZero = this.getAngle();
+
+  }
+
+  public double getZeroAngle() {
+    return this.gyroZero;
+  }
+
   @Override
   protected void initDefaultCommand() {
     setDefaultCommand(new JoystickDrive());