add comments cindy/PIDshooter/Parked
authorCindy Zhang <cindyzyx9@gmail.com>
Mon, 15 Feb 2016 23:23:29 +0000 (15:23 -0800)
committerCindy Zhang <cindyzyx9@gmail.com>
Mon, 15 Feb 2016 23:24:30 +0000 (15:24 -0800)
src/org/usfirst/frc/team3501/robot/subsystems/Shooter.java

index 590f4d59ee6ec6817c3071b770b00dc70b0d1209..9a2dbb7ddb16c5d96db3f08f608df45bb40b380a 100755 (executable)
@@ -17,10 +17,17 @@ import edu.wpi.first.wpilibj.command.PIDSubsystem;
  *
  * @author superuser
  *
+ *         setPoint (in the context of shooter) is the target value we want the
+ *         PID controller to adjust the system to, for example, if we want the
+ *         shooter wheels to run at 10in/s
+ *
  */
 
 public class Shooter extends PIDSubsystem {
+  // Shooter PID Proportional Constants P, I, and D
   private static double sp = 0.015, si = 0, sd = 0;
+
+  // PID Controller tolerance for the error
   private static double encoderTolerance = 5.0;
   private static double pidOutput = 5.0;
 
@@ -73,7 +80,7 @@ public class Shooter extends PIDSubsystem {
   }
 
   public double getSpeed() {
-    return encoder.getRate();
+    return encoder.getRate(); // in/sec
   }
 
   // Use negative # for decrement. Positive for increment.
@@ -113,6 +120,13 @@ public class Shooter extends PIDSubsystem {
     return sensorFeedback();
   }
 
+  /*
+   * 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
+   */
   @Override
   protected void usePIDOutput(double output) {
     shooter.set(output);
@@ -131,6 +145,7 @@ public class Shooter extends PIDSubsystem {
     this.enable();
   }
 
+  // Updates the PID constants
   public void updatePID() {
     this.getPIDController().setPID(sp, si, sd);
   }