add code for switching b/w cameras
[3501/stronghold-2016] / src / org / usfirst / frc / team3501 / robot / subsystems / DriveTrain.java
index a4bba48b5fe7bd276b372f0144995d81493d7daf..807bb151ec2d3b239329c3f9aafeabd41ff438f8 100644 (file)
@@ -1,36 +1,32 @@
 package org.usfirst.frc.team3501.robot.subsystems;
 
+import org.usfirst.frc.team3501.robot.CheesyDriveHelper;
 import org.usfirst.frc.team3501.robot.Constants;
-import org.usfirst.frc.team3501.robot.MathLib;
 import org.usfirst.frc.team3501.robot.commands.driving.JoystickDrive;
-import org.usfirst.frc.team3501.robot.sensors.GyroLib;
-import org.usfirst.frc.team3501.robot.sensors.Lidar;
 
 import edu.wpi.first.wpilibj.CANTalon;
 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 {
-  // Current Drive Mode Default Drive Mode is Manual
-  private int DRIVE_MODE = 1;
+  // Determines if the "front" of the robot has been reversed
+  private boolean outputFlipped = false;
+
   private static double pidOutput = 0;
 
   private Encoder leftEncoder, rightEncoder;
 
-  public static Lidar leftLidar;
-  public static Lidar rightLidar;
-
   private CANTalon frontLeft, frontRight, rearLeft, rearRight;
   private RobotDrive robotDrive;
 
-  private GyroLib gyro;
   private DoubleSolenoid leftGearPiston, rightGearPiston;
 
+  private CheesyDriveHelper cheese;
+
   // Drivetrain specific constants that relate to the inches per pulse value for
   // the encoders
 
@@ -38,16 +34,13 @@ public class DriveTrain extends PIDSubsystem {
     super(Constants.DriveTrain.kp, Constants.DriveTrain.ki,
         Constants.DriveTrain.kd);
 
-    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);
+    frontLeft = new CANTalon(Constants.DriveTrain.DRIVE_FRONT_LEFT);
+    frontRight = new CANTalon(Constants.DriveTrain.DRIVE_FRONT_RIGHT);
+    rearLeft = new CANTalon(Constants.DriveTrain.DRIVE_REAR_LEFT);
+    rearRight = new CANTalon(Constants.DriveTrain.DRIVE_REAR_RIGHT);
 
     robotDrive = new RobotDrive(frontLeft, rearLeft, frontRight, rearRight);
 
-    leftLidar = new Lidar(I2C.Port.kOnboard);
-    rightLidar = new Lidar(I2C.Port.kOnboard); // TODO: find port for second
-    // lidar
     leftEncoder = new Encoder(Constants.DriveTrain.ENCODER_LEFT_A,
         Constants.DriveTrain.ENCODER_LEFT_B, false, EncodingType.k4X);
     rightEncoder = new Encoder(Constants.DriveTrain.ENCODER_RIGHT_A,
@@ -58,18 +51,17 @@ 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_SHIFT_MODULE,
+        Constants.DriveTrain.LEFT_SHIFT_FORWARD,
+        Constants.DriveTrain.LEFT_SHIFT_REVERSE);
+    rightGearPiston = new DoubleSolenoid(
+        Constants.DriveTrain.RIGHT_SHIFT_MODULE,
+        Constants.DriveTrain.RIGHT_SHIFT_FORWARD,
+        Constants.DriveTrain.RIGHT_SHIFT_REVERSE);
+
+    cheese = new CheesyDriveHelper(this);
   }
 
   @Override
@@ -98,7 +90,7 @@ public class DriveTrain extends PIDSubsystem {
   }
 
   public void stop() {
-    drive(0, 0);
+    setMotorSpeeds(0, 0);
   }
 
   public void resetEncoders() {
@@ -106,14 +98,6 @@ public class DriveTrain extends PIDSubsystem {
     rightEncoder.reset();
   }
 
-  public double getLeftLidarDistance() {
-    return leftLidar.pidGet();
-  }
-
-  public double getsRightLidarDistance() {
-    return rightLidar.pidGet();
-  }
-
   public double getRightSpeed() {
     return rightEncoder.getRate(); // in inches per second
   }
@@ -137,18 +121,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) {
@@ -159,10 +132,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
    */
@@ -172,12 +141,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(Constants.DriveTrain.kp,
-          Constants.DriveTrain.ki, Constants.DriveTrain.kd);
-    else
-      this.getPIDController().setPID(Constants.DriveTrain.gp,
-          Constants.DriveTrain.gd, Constants.DriveTrain.gi);
+    this.getPIDController().setPID(Constants.DriveTrain.kp,
+        Constants.DriveTrain.ki, Constants.DriveTrain.kd);
   }
 
   public CANTalon getFrontLeft() {
@@ -196,10 +161,6 @@ 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
@@ -213,17 +174,12 @@ public class DriveTrain extends PIDSubsystem {
   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 * Constants.DriveTrain.kp / 10;
-    } else if (DRIVE_MODE == Constants.DriveTrain.GYRO_MODE) {
-      left = output;
-      right = -output;
-    }
-    drive(left, right);
+    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;
+    setMotorSpeeds(left, right);
     pidOutput = output;
   }
 
@@ -235,140 +191,83 @@ 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;
-  }
-
-  /*
-   * @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
-   */
-  public void drive(double left, double right) {
-    robotDrive.tankDrive(-left, -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(Constants.DriveTrain.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(Constants.DriveTrain.gp,
-        Constants.DriveTrain.gi, Constants.DriveTrain.gd);
-
-    this.setAbsoluteTolerance(Constants.DriveTrain.gyroTolerance);
-    this.setOutputRange(-1.0, 1.0);
-    this.setInputRange(-360.0, 360.0);
-    this.enable();
+    return getAvgEncoderDistance();
   }
 
-  /*
-   * 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);
+  public void joystickDrive(double left, double right) {
+    // Handle flipping of the "front" of the robot
+    double k = (isFlipped() ? -1 : 1);
+    cheese.cheesyDrive(-left * k, -right,
+        getGearPistonValue() == Constants.DriveTrain.HIGH_GEAR);
   }
 
   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);
+    double k = (isFlipped() ? -1 : 1);
+    /*
+     * cheese.cheesyDrive(-left * k, -right, getGearPistonValue() ==
+     * Constants.DriveTrain.HIGH_GEAR);
+     */
+
+    frontLeft.set(left);
+    rearLeft.set(left);
     frontRight.set(right);
     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;
+  }
+
 }