+
+ private double sensorFeedback() {
+ if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
+ return getAvgEncoderDistance();
+ else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE)
+ return -this.getGyroAngle();
+ // counterclockwise is positive on joystick but we want it to be negative
+ else
+ return 0;
+ }
+
+ public void drive(double left, double right) {
+ robotDrive.tankDrive(-left, -right);
+ // dunno why but inverted drive (- values is forward)
+ }
+
+ public void driveDistance(double dist, double maxTimeOut) {
+ dist = MathLib.constrain(dist, -100, 100);
+ setEncoderPID();
+ setSetpoint(dist);
+ }
+
+ public void setEncoderPID() {
+ DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
+ this.updatePID();
+ this.setAbsoluteTolerance(encoderTolerance);
+ this.setOutputRange(-1.0, 1.0);
+ this.setInputRange(-200.0, 200.0);
+ this.enable();
+ }
+
+ private void setGyroPID() {
+ DRIVE_MODE = Constants.DriveTrain.GYRO_MODE;
+ this.updatePID();
+ this.getPIDController().setPID(gp, gi, gd);
+
+ this.setAbsoluteTolerance(gyroTolerance);
+ this.setOutputRange(-1.0, 1.0);
+ this.setInputRange(-360.0, 360.0);
+ this.enable();
+ }
+
+ public void turnAngle(double angle) {
+ angle = MathLib.constrain(angle, -360, 360);
+ setGyroPID();
+ setSetpoint(angle);
+ }
+
+ public void setMotorSpeeds(double left, double right) {
+ // positive setpoint to left side makes it go backwards
+ // positive setpoint to right side makes it go forwards.
+ frontLeft.set(-left);
+ rearLeft.set(-left);
+ frontRight.set(right);
+ rearRight.set(right);
+ }
+
+ private static double kp = 0.013, ki = 0.000015, kd = -0.002;
+ private static double gp = 0.018, gi = 0.000015, gd = 0;