summaryrefslogtreecommitdiff
path: root/src/org/usfirst/frc/team4272/robotlib
diff options
context:
space:
mode:
authorLuke Shumaker <lukeshu@sbcglobal.net>2016-01-27 21:45:04 -0500
committerLuke Shumaker <lukeshu@sbcglobal.net>2016-01-27 21:45:04 -0500
commita07b8d0a24a2c3c66978d8199604219a0ed8bcc8 (patch)
tree7c9d9ffeb9397c944ec759bed61828528b421ce4 /src/org/usfirst/frc/team4272/robotlib
parent20c0715af72b3a089f3aa17fa6f0da5992dc9f29 (diff)
clean up PIDController
Diffstat (limited to 'src/org/usfirst/frc/team4272/robotlib')
-rw-r--r--src/org/usfirst/frc/team4272/robotlib/PIDController.java44
1 files changed, 29 insertions, 15 deletions
diff --git a/src/org/usfirst/frc/team4272/robotlib/PIDController.java b/src/org/usfirst/frc/team4272/robotlib/PIDController.java
index 14c26ce..13f5666 100644
--- a/src/org/usfirst/frc/team4272/robotlib/PIDController.java
+++ b/src/org/usfirst/frc/team4272/robotlib/PIDController.java
@@ -41,17 +41,14 @@ import edu.wpi.first.wpilibj.SpeedController;
/**
* An enhanced variant of {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController}
* (implements a PID Control Loop).
- *
+ * <p>
* It is enhanced from
* {@link edu.wpi.first.wpilibj.PIDController wpilibj PIDController}
* in that it that also:
- *
* <ul>
* <li> implements SpeedController (and therefore PIDOutput)
- * <li> has auto-enable/disable functionality to avoid "locking" the
- * motor when the setpoint is 0.
- *
- * @author Luke Shumaker <lukeshu@sbcglobal.net>
+ * <li> disables self if the setpoint is NaN (see {@link PIDNanny}).
+ * </ul>
*/
public class PIDController extends edu.wpi.first.wpilibj.PIDController implements SpeedController {
private boolean NaNDisabled = false;
@@ -86,6 +83,15 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
/**
* Convenience constructor with {@code Kf} defaulting to
* {@code 0.0}.
+ *
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output percentage
+ * @param period the loop time for doing calculations. This particularly
+ * effects calculations of the integral and differential terms. The
+ * default is 50ms.
*/
public PIDController(double Kp, double Ki, double Kd,
PIDSource source, PIDOutput output,
@@ -96,6 +102,13 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
/**
* Convenience constructor with {@code period} defaulting to
* {@link #kDefaultPeriod}.
+ *
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param Kf the feed forward term
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output percentage
*/
public PIDController(double Kp, double Ki, double Kd, double Kf,
PIDSource source, PIDOutput output) {
@@ -106,6 +119,12 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
* Convenience constructor with {@code Kf} defaulting to
* {@code 0.0}, and {@code period} defaulting to
* {@link #kDefaultPeriod}.
+ *
+ * @param Kp the proportional coefficient
+ * @param Ki the integral coefficient
+ * @param Kd the derivative coefficient
+ * @param source The PIDSource object that is used to get values
+ * @param output The PIDOutput object that is set to the output percentage
*/
public PIDController(double Kp, double Ki, double Kd,
PIDSource source, PIDOutput output) {
@@ -169,15 +188,10 @@ public class PIDController extends edu.wpi.first.wpilibj.PIDController implement
}
/**
- * Don't use this; it is leaking up from
- * {@link edu.wpi.first.wpilibj.CANJaguar CANJaguar} through
- * {@link edu.wpi.first.wpilibj.SpeedController SpeedController}
- *
- * @param output
- * @param syncGroup
- *
- * @deprecated Don't use this, it is leaking up from
- * {@link edu.wpi.first.wpilibj.CANJaguar CANJaguar}
+ * Don't use this.
+ * @deprecated Don't use this; it is leaking up from
+ * {@link edu.wpi.first.wpilibj.CANJaguar} through
+ * {@link edu.wpi.first.wpilibj.SpeedController}
*/
@Override
public void set(double output, byte syncGroup) {