Purge code of all unused fields/classes. Only testing code.
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index d212059b1c5b91770ae1a0ec6265f403f2672d00..5f370e98baee876cf422f749fe286b6b1935656e 100644 (file)
@@ -1,8 +1,6 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
 import org.usfirst.frc.team3501.robot.Constants;
-import org.usfirst.frc.team3501.robot.GyroLib;
-import org.usfirst.frc.team3501.robot.MathLib;
 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
 
 import edu.wpi.first.wpilibj.CANTalon;
@@ -10,43 +8,26 @@ import edu.wpi.first.wpilibj.CounterBase.EncodingType;
 import edu.wpi.first.wpilibj.DoubleSolenoid;
 import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
 import edu.wpi.first.wpilibj.Encoder;
-import edu.wpi.first.wpilibj.I2C;
 import edu.wpi.first.wpilibj.RobotDrive;
 import edu.wpi.first.wpilibj.command.PIDSubsystem;
 
 public class DriveTrain extends PIDSubsystem {
-  /*
-   * A setpoint is the value we want the PID controller to attempt to adjust the
-   * system to
-   * In other words, If we want to drive the robot 4 meters, the setpoint would
-   * be 4 meters
-   */
-
-  // Encoder PID Proportional Constants P, I, and D
-  private static double EP = 0.013, EI = 0.000015, ED = -0.002;
-
-  // Gyro PID Constants P, I, and D
-  private static double GP = 0.018, GI = 0.000015, GD = 0;
+  private boolean outputFlipped = false;
   private static double pidOutput = 0;
 
-  // PID Controller tolerances for the error
-  private static double encoderTolerance = 8.0, gyroTolerance = 5.0;
-
-  // Current Drive Mode Default Drive Mode is Manual
-  private int DRIVE_MODE = 1;
-
-  // Different Drive Modes
-  private static final int MANUAL_MODE = 1, ENCODER_MODE = 2, GYRO_MODE = 3;
-
   private Encoder leftEncoder, rightEncoder;
+
   private CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private RobotDrive robotDrive;
 
-  private GyroLib gyro;
   private DoubleSolenoid leftGearPiston, rightGearPiston;
 
+  // Drivetrain specific constants that relate to the inches per pulse value for
+  // the encoders
+
   public DriveTrain() {
-    super(EP, EI, ED);
+    super(Constants.DriveTrain.kp, Constants.DriveTrain.ki,
+        Constants.DriveTrain.kd);
 
     frontLeft = new CANTalon(Constants.DriveTrain.FRONT_LEFT);
     frontRight = new CANTalon(Constants.DriveTrain.FRONT_RIGHT);
@@ -54,6 +35,7 @@ public class DriveTrain extends PIDSubsystem {
     rearRight = new CANTalon(Constants.DriveTrain.REAR_RIGHT);
 
     robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
+
     leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
         Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
     rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
@@ -64,18 +46,12 @@ public class DriveTrain extends PIDSubsystem {
     leftEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
     rightEncoder.setDistancePerPulse(Constants.DriveTrain.INCHES_PER_PULSE);
 
-    gyro = new GyroLib(I2C.Port.kOnboard, false);
-
-    DRIVE_MODE = Constants.DriveTrain.ENCODER_MODE;
-    setEncoderPID();
     this.disable();
-    gyro.start();
 
-    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_FORWARD,
-        Constants.DriveTrain.LEFT_REVERSE);
-    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_FORWARD,
-        Constants.DriveTrain.RIGHT_REVERSE);
-    Constants.DriveTrain.inverted = false;
+    leftGearPiston = new DoubleSolenoid(Constants.DriveTrain.LEFT_MODULE,
+        Constants.DriveTrain.LEFT_FORWARD, Constants.DriveTrain.LEFT_REVERSE);
+    rightGearPiston = new DoubleSolenoid(Constants.DriveTrain.RIGHT_MODULE,
+        Constants.DriveTrain.RIGHT_FORWARD, Constants.DriveTrain.RIGHT_REVERSE);
   }
 
   @Override
@@ -135,18 +111,7 @@ public class DriveTrain extends PIDSubsystem {
   // Get error between the setpoint of PID Controller and the current state of
   // the robot
   public double getError() {
-    if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
-      return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
-    else
-      return Math.abs(this.getSetpoint() + getGyroAngle());
-  }
-
-  public double getGyroAngle() {
-    return gyro.getRotationZ().getAngle();
-  }
-
-  public void resetGyro() {
-    gyro.reset();
+    return Math.abs(this.getSetpoint() - getAvgEncoderDistance());
   }
 
   public void printEncoder(int i, int n) {
@@ -157,10 +122,6 @@ public class DriveTrain extends PIDSubsystem {
     }
   }
 
-  public void printGyroOutput() {
-    System.out.println("Gyro Angle" + -this.getGyroAngle());
-  }
-
   /*
    * returns the PID output that is returned by the PID Controller
    */
@@ -170,10 +131,8 @@ public class DriveTrain extends PIDSubsystem {
 
   // Updates the PID constants based on which control mode is being used
   public void updatePID() {
-    if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE)
-      this.getPIDController().setPID(EP, EI, ED);
-    else
-      this.getPIDController().setPID(GP, GD, GI);
+    this.getPIDController().setPID(Constants.DriveTrain.kp,
+        Constants.DriveTrain.ki, Constants.DriveTrain.kd);
   }
 
   public CANTalon getFrontLeft() {
@@ -192,34 +151,24 @@ public class DriveTrain extends PIDSubsystem {
     return rearRight;
   }
 
-  public int getMode() {
-    return DRIVE_MODE;
-  }
-
   /*
    * Method is a required method that the PID Subsystem uses to return the
    * calculated PID value to the driver
-   *
+   * 
    * @param Gives the user the output from the PID algorithm that is calculated
    * internally
-   *
+   * 
    * Body: Uses the output, does some filtering and drives the robot
    */
   @Override
   protected void usePIDOutput(double output) {
     double left = 0;
     double right = 0;
-    if (DRIVE_MODE == Constants.DriveTrain.ENCODER_MODE) {
-      double drift = this.getLeftDistance() - this.getRightDistance();
-      if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
-        output = Math.signum(output) * 0.3;
-      left = output;
-      right = output + drift * EP / 10;
-    }
-    else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) {
-      left = output;
-      right = -output;
-    }
+    double drift = this.getLeftDistance() - this.getRightDistance();
+    if (Math.abs(output) > 0 && Math.abs(output) < 0.3)
+      output = Math.signum(output) * 0.3;
+    left = output;
+    right = output + drift * Constants.DriveTrain.kp / 10;
     drive(left, right);
     pidOutput = output;
   }
@@ -231,93 +180,22 @@ public class DriveTrain extends PIDSubsystem {
 
   /*
    * Checks the drive mode
-   *
-   * @return the current state of the robot in each state
-   * Average distance from both sides of tank drive for Encoder Mode
-   * Angle from the gyro in GYRO_MODE
+   * 
+   * @return the current state of the robot in each state Average distance from
+   * both sides of tank drive for Encoder Mode Angle from the gyro in GYRO_MODE
    */
   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;
+    return getAvgEncoderDistance();
   }
 
   /*
    * @param left and right setpoints to set to the left and right side of tank
    * inverted is for Logan, wants the robot to invert all controls left = right
-   * and right = left
-   * negative input is required for the regular rotation because RobotDrive
-   * tankdrive method drives inverted
+   * and right = left negative input is required for the regular rotation
+   * because RobotDrive tankdrive method drives inverted
    */
   public void drive(double left, double right) {
-    // dunno why but inverted drive (- values is forward)
-    if (!Constants.DriveTrain.inverted)
-      robotDrive.tankDrive(-left,
-          -right);
-    else
-      robotDrive.tankDrive(right, left);
-  }
-
-  /*
-   * constrains the distance to within -100 and 100 since we aren't going to
-   * drive more than 100 inches
-   * 
-   * Configure Encoder PID
-   * 
-   * Sets the setpoint to the PID subsystem
-   */
-  public void driveDistance(double dist, double maxTimeOut) {
-    dist = MathLib.constrain(dist, -100, 100);
-    setEncoderPID();
-    setSetpoint(dist);
-  }
-
-  /*
-   * Sets the encoder mode
-   * Updates the PID constants sets the tolerance and sets output/input ranges
-   * Enables the PID controllers
-   */
-  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();
-  }
-
-  /*
-   * Sets the Gyro Mode
-   * Updates the PID constants, sets the tolerance and sets output/input ranges
-   * Enables the PID controllers
-   */
-  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();
-  }
-
-  /*
-   * Turning method that should be used repeatedly in a command
-   *
-   * First constrains the angle to within -360 and 360 since that is as much as
-   * we need to turn
-   *
-   * Configures Gyro PID and sets the setpoint as an angle
-   */
-  public void turnAngle(double angle) {
-    angle = MathLib.constrain(angle, -360, 360);
-    setGyroPID();
-    setSetpoint(angle);
+    robotDrive.tankDrive(-left, -right);
   }
 
   public void setMotorSpeeds(double left, double right) {
@@ -329,41 +207,56 @@ public class DriveTrain extends PIDSubsystem {
     rearRight.set(right);
   }
 
-  /*
-   * @return a value that is the current setpoint for the piston
-   * kReverse or kForward
-   */
-  public Value getLeftGearPistonValue() {
-    return leftGearPiston.get();
-  }
-
-  /*
-   * @return a value that is the current setpoint for the piston
-   * kReverse or kForward
+  /**
+   * @return a value that is the current setpoint for the piston (kReverse or
+   *         kForward)
    */
-  public Value getRightGearPistonValue() {
-    return rightGearPiston.get();
+  public Value getGearPistonValue() {
+    return leftGearPiston.get(); // Pistons should always be in the same state
   }
 
-  /*
+  /**
    * Changes the ball shift gear assembly to high
    */
   public void setHighGear() {
     changeGear(Constants.DriveTrain.HIGH_GEAR);
   }
 
-  /*
+  /**
    * Changes the ball shift gear assembly to low
    */
   public void setLowGear() {
     changeGear(Constants.DriveTrain.LOW_GEAR);
   }
 
-  /*
-   * changes the gear to a DoubleSolenoid.Value
+  /**
+   * Changes the gear to a DoubleSolenoid.Value
    */
   public void changeGear(DoubleSolenoid.Value gear) {
     leftGearPiston.set(gear);
     rightGearPiston.set(gear);
   }
+
+  /**
+   * Switches drivetrain gears from high to low or low to high
+   */
+  public void switchGear() {
+    Value currentValue = getGearPistonValue();
+    Value setValue = (currentValue == Constants.DriveTrain.HIGH_GEAR) ? Constants.DriveTrain.LOW_GEAR
+        : Constants.DriveTrain.HIGH_GEAR;
+    changeGear(setValue);
+  }
+
+  /**
+   * Toggle whether the motor outputs are flipped, effectively switching which
+   * side of the robot is the front.
+   */
+  public void toggleFlipped() {
+    outputFlipped = !outputFlipped;
+  }
+
+  public boolean isFlipped() {
+    return outputFlipped;
+  }
+
 }