fix bugs
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 1e9bb33e7428677f1a83e9374e1052229206afe5..44744c4a078fa0f0edca7d3b0a6ca5e2290b481a 100644 (file)
@@ -2,19 +2,33 @@ 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.009, 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
+      / ENCODER_PULSES_PER_REVOLUTION;
+
   private static DriveTrain driveTrain;
   private final CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private final RobotDrive robotDrive;
   private final Encoder leftEncoder, rightEncoder;
 
+  private BNO055 imu;
+
   private DriveTrain() {
     // MOTOR CONTROLLERS
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
@@ -24,15 +38,19 @@ public class DriveTrain extends Subsystem {
 
     // ENCODERS
     leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
-        Constants.DriveTrain.ENCODER_LEFT_B);
+        Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
     rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
-        Constants.DriveTrain.ENCODER_RIGHT_B);
+        Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
 
-    leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
-    rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
+    leftEncoder.setDistancePerPulse(INCHES_PER_PULSE);
+    rightEncoder.setDistancePerPulse(INCHES_PER_PULSE);
 
     // 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() {
@@ -47,12 +65,12 @@ public class DriveTrain extends Subsystem {
     frontLeft.set(left);
     rearLeft.set(left);
 
-    frontRight.set(right);
-    rearRight.set(right);
+    frontRight.set(-right);
+    rearRight.set(-right);
   }
 
   public void joystickDrive(final double thrust, final double twist) {
-    robotDrive.arcadeDrive(thrust, twist);
+    robotDrive.arcadeDrive(thrust, twist, true);
   }
 
   public void stop() {
@@ -75,32 +93,21 @@ public class DriveTrain extends Subsystem {
     return frontLeft.get();
   }
 
-  public CANTalon getFrontLeft() {
-    return frontLeft;
-  }
-
-  public CANTalon getFrontRight() {
-    return frontRight;
-  }
-
-  public CANTalon getRearLeft() {
-    return rearLeft;
-  }
-
-  public CANTalon getRearRight() {
-    return rearRight;
-  }
-
   // ENCODER METHODS
 
-  public double getLeftEncoder() {
+  public double getLeftEncoderDistance() {
     return leftEncoder.getDistance();
   }
 
-  public double getRightEncoder() {
+  public double getRightEncoderDistance() {
     return rightEncoder.getDistance();
   }
 
+  public void printEncoderOutput() {
+    System.out.println("left: " + getLeftEncoderDistance());
+    System.out.println("right: " + getRightEncoderDistance());
+  }
+
   public double getAvgEncoderDistance() {
     return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
   }
@@ -122,6 +129,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());