finish implement driveDistance and TurnForAngle using PID algorithm
[3501/2017steamworks] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index 426063628b9b5cd45a0e59f656f474aaa0c902c1..c445f630109f1d4d30067f6735fb65e8c5a6395c 100644 (file)
 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 {
-    private static DriveTrain driveTrain;
-    private CANTalon frontLeft, frontRight, rearLeft, rearRight;
-    private RobotDrive robotDrive;
-    private Encoder leftEncoder, rightEncoder;
-
-    private DriveTrain() {
-        // MOTOR CONTROLLERS
-        frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
-        frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
-        rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
-        rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
-
-        // ENCODERS
-        leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
-                Constants.DriveTrain.ENCODER_LEFT_B);
-        rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
-                Constants.DriveTrain.ENCODER_RIGHT_B);
-
-        leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
-        rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
-
-        // ROBOT DRIVE
-        robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
-    }
-
-    public static DriveTrain getDriveTrain() {
-        if (driveTrain == null)
-            driveTrain = new DriveTrain();
-        return driveTrain;
-    }
-
-    public void setMotorSpeeds(double left, double right) {
-        robotDrive.tankDrive(left, right);
-    }
-
-    // ENCODER METHODS
-
-    public double getLeftEncoder() {
-        return leftEncoder.getDistance();
-    }
-
-    public double getRightEncoder() {
-        return rightEncoder.getDistance();
-    }
-
-    public double getAvgEncoderDistance() {
-        return (leftEncoder.getDistance() + rightEncoder.getDistance()) / 2;
-    }
-
-    public void resetEncoders() {
-        leftEncoder.reset();
-        rightEncoder.reset();
-    }
-
-    public double getLeftSpeed() {
-        return leftEncoder.getRate();
-    }
-
-    public double getRightSpeed() {
-        return rightEncoder.getRate();
-    }
-
-    public double getSpeed() {
-        return (getLeftSpeed() + getRightSpeed()) / 2.0;
-    }
-
-    @Override
-    protected void initDefaultCommand() {
+  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
+      / 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);
+    frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
+    rearLeft = new CANTalon(Constants.DriveTrain.REAR_LEFT);
+    rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
+
+    // ENCODERS
+    leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
+        Constants.DriveTrain.ENCODER_LEFT_B, false, Encoder.EncodingType.k4X);
+    rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
+        Constants.DriveTrain.ENCODER_RIGHT_B, false, Encoder.EncodingType.k4X);
+
+    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() {
+    if (driveTrain == null) {
+      driveTrain = new DriveTrain();
     }
+    return driveTrain;
+  }
+
+  // DRIVE METHODS
+  public void setMotorValues(final double left, final double right) {
+    frontLeft.set(left);
+    rearLeft.set(left);
+
+    frontRight.set(-right);
+    rearRight.set(-right);
+  }
+
+  public void joystickDrive(final double thrust, final double twist) {
+    robotDrive.arcadeDrive(thrust, twist, true);
+  }
+
+  public void stop() {
+    setMotorValues(0, 0);
+  }
+
+  public double getLeftMotorVal() {
+    return (frontLeft.get() + rearLeft.get()) / 2;
+  }
+
+  public double getRightMotorVal() {
+    return (frontRight.get() + rearRight.get()) / 2;
+  }
+
+  // ENCODER METHODS
+
+  public double getLeftEncoderDistance() {
+    return leftEncoder.getDistance();
+  }
+
+  public double getRightEncoderDistance() {
+    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;
+  }
+
+  public void resetEncoders() {
+    leftEncoder.reset();
+    rightEncoder.reset();
+  }
+
+  public double getLeftSpeed() {
+    return leftEncoder.getRate();
+  }
+
+  public double getRightSpeed() {
+    return rightEncoder.getRate();
+  }
+
+  public double getSpeed() {
+    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());
+  }
 
 }