From 53c41aa461cc0984b3c377dede21247c2242e248 Mon Sep 17 00:00:00 2001 From: CaseyManning Date: Thu, 23 Mar 2017 16:28:08 -0700 Subject: [PATCH 1/5] preliminary implementation of deadband Written in sublime text. --- .../CustomPIDController.java | 23 +++++++++++++++++++ 1 file changed, 23 insertions(+) diff --git a/custom/motioncontrollers/CustomPIDController.java b/custom/motioncontrollers/CustomPIDController.java index 502e62f1..940fb3c5 100644 --- a/custom/motioncontrollers/CustomPIDController.java +++ b/custom/motioncontrollers/CustomPIDController.java @@ -24,6 +24,7 @@ public class CustomPIDController extends MotionController { protected double lastError; protected long lastTime; protected double minimumNominalOutput = 0.0; + protected double deadband = 0.0; /** * An extremely basic PID controller. @@ -168,6 +169,17 @@ public double getMinimumNominalOutput() { return minimumNominalOutput; } + + /** + * + * @return + * The current deadband value + */ + public double getDeadband() { + return deadband; + } + + /** * Sets the parameters of the PID loop * @@ -223,6 +235,15 @@ public void setMinimumNominalOutput(double minimumNominalOutput) { this.minimumNominalOutput = minimumNominalOutput; } + /** + * + * @param deadband + */ + public void setDeadband(double deadband) { + this.deadband = deadband; + } + + /** * Sets the threshold below which the I term becomes active. * When the I term is active, the error sum increases. When @@ -329,6 +350,8 @@ public double getSafely() throws InvalidSensorException { } if (Math.abs(result) < minimumNominalOutput) { result = Math.signum(result) * minimumNominalOutput; + } else if (Math.abs(result) < deadband) { + result = 0; } return result; } From c9f836a2a041c3112fcc6a80b622376b97b5c975 Mon Sep 17 00:00:00 2001 From: CaseyManning Date: Thu, 23 Mar 2017 16:43:56 -0700 Subject: [PATCH 2/5] changed to throw error if both deadband and minimum nominal output are set --- custom/motioncontrollers/CustomPIDController.java | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/custom/motioncontrollers/CustomPIDController.java b/custom/motioncontrollers/CustomPIDController.java index 940fb3c5..749db1f4 100644 --- a/custom/motioncontrollers/CustomPIDController.java +++ b/custom/motioncontrollers/CustomPIDController.java @@ -169,7 +169,6 @@ public double getMinimumNominalOutput() { return minimumNominalOutput; } - /** * * @return @@ -179,7 +178,6 @@ public double getDeadband() { return deadband; } - /** * Sets the parameters of the PID loop * @@ -232,14 +230,23 @@ public void setPIDF(double P, double I, double D, double F) { * the motor can only run well above a value. */ public void setMinimumNominalOutput(double minimumNominalOutput) { + if(deadband > 0) { + LogKitten.ex("Cannot set both PID deadband and minimum nominal output"); + } + deadband = 0; this.minimumNominalOutput = minimumNominalOutput; } /** * * @param deadband + * PID output will be set to 0 if it is lower than the deadband */ public void setDeadband(double deadband) { + if(minimumNominalOutput > 0) { + LogKitten.ex("Cannot set both PID deadband and minimum nominal output"); + } + minimumNominalOutput = 0; this.deadband = deadband; } From e3861f82bc79d02e34ac087c38fbaa83e8b25dcd Mon Sep 17 00:00:00 2001 From: CaseyManning Date: Fri, 24 Mar 2017 16:07:28 -0700 Subject: [PATCH 3/5] fixed error messages --- .../CustomPIDController.java | 176 +++++++++--------- 1 file changed, 86 insertions(+), 90 deletions(-) diff --git a/custom/motioncontrollers/CustomPIDController.java b/custom/motioncontrollers/CustomPIDController.java index 749db1f4..3256b391 100644 --- a/custom/motioncontrollers/CustomPIDController.java +++ b/custom/motioncontrollers/CustomPIDController.java @@ -1,17 +1,17 @@ package org.usfirst.frc4904.standard.custom.motioncontrollers; - import org.usfirst.frc4904.standard.LogKitten; import org.usfirst.frc4904.standard.custom.sensors.InvalidSensorException; import org.usfirst.frc4904.standard.custom.sensors.NativeDerivativeSensor; import org.usfirst.frc4904.standard.custom.sensors.PIDSensor; + import edu.wpi.first.wpilibj.PIDSource; import edu.wpi.first.wpilibj.PIDSourceType; import edu.wpi.first.wpilibj.util.BoundaryException; /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate and + * distance. * */ public class CustomPIDController extends MotionController { @@ -27,19 +27,19 @@ public class CustomPIDController extends MotionController { protected double deadband = 0.0; /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param F - * Initial F (feed forward) constant + * Initial F (feed forward) constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, double F, PIDSensor sensor) { super(sensor); @@ -50,19 +50,19 @@ public CustomPIDController(double P, double I, double D, double F, PIDSensor sen } /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param F - * Initial F (feed forward) constant + * Initial F (feed forward) constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, double F, PIDSource source) { super(source); @@ -73,88 +73,84 @@ public CustomPIDController(double P, double I, double D, double F, PIDSource sou } /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, PIDSensor sensor) { this(P, I, D, 0.0, sensor); } /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, PIDSource source) { this(P, I, D, 0.0, source); } /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(PIDSensor sensor) { this(0, 0, 0, sensor); } /** - * An extremely basic PID controller. - * It does not differentiate between rate and distance. + * An extremely basic PID controller. It does not differentiate between rate + * and distance. * * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(PIDSource source) { this(0, 0, 0, source); } /** - * @return - * The current P value + * @return The current P value */ public double getP() { return P; } /** - * @return - * The current I value + * @return The current I value */ public double getI() { return I; } /** - * @return - * The current D value + * @return The current D value */ public double getD() { return D; } /** - * @return - * The current F (feed forward) value + * @return The current F (feed forward) value */ public double getF() { return F; @@ -162,8 +158,7 @@ public double getF() { /** * - * @return - * The current minimumNominalOutput (minimum nominal output) value + * @return The current minimumNominalOutput (minimum nominal output) value */ public double getMinimumNominalOutput() { return minimumNominalOutput; @@ -171,8 +166,7 @@ public double getMinimumNominalOutput() { /** * - * @return - * The current deadband value + * @return The current deadband value */ public double getDeadband() { return deadband; @@ -182,14 +176,14 @@ public double getDeadband() { * Sets the parameters of the PID loop * * @param P - * Proportional + * Proportional * @param I - * Integral + * Integral * @param D - * Derivative + * Derivative * - * If you do not know what these mean, please refer - * to this link: https://en.wikipedia.org/wiki/PID_controller + * If you do not know what these mean, please refer to this link: + * https://en.wikipedia.org/wiki/PID_controller */ public void setPID(double P, double I, double D) { this.P = P; @@ -201,16 +195,16 @@ public void setPID(double P, double I, double D) { * Sets the parameters of the PID loop * * @param P - * Proportional + * Proportional * @param I - * Integral + * Integral * @param D - * Derivative + * Derivative * @param F - * Feed forward (scalar on input added to output) + * Feed forward (scalar on input added to output) * - * If you do not know what these mean, please refer - * to this link: https://en.wikipedia.org/wiki/PID_controller + * If you do not know what these mean, please refer to this link: + * https://en.wikipedia.org/wiki/PID_controller */ public void setPIDF(double P, double I, double D, double F) { this.P = P; @@ -222,16 +216,13 @@ public void setPIDF(double P, double I, double D, double F) { /** * * @param minimumNominalOutput - * Minimum Nominal Output - * result will be set to - * ±this value if the absolute - * value of the result is less than - * this value. This is useful if - * the motor can only run well above a value. + * Minimum Nominal Output result will be set to ±this value if + * the absolute value of the result is less than this value. This + * is useful if the motor can only run well above a value. */ public void setMinimumNominalOutput(double minimumNominalOutput) { - if(deadband > 0) { - LogKitten.ex("Cannot set both PID deadband and minimum nominal output"); + if (deadband > 0) { + LogKitten.e("Removing deadband in favor of minimum nominal output"); } deadband = 0; this.minimumNominalOutput = minimumNominalOutput; @@ -240,21 +231,20 @@ public void setMinimumNominalOutput(double minimumNominalOutput) { /** * * @param deadband - * PID output will be set to 0 if it is lower than the deadband + * PID output will be set to 0 if it is lower than the deadband */ public void setDeadband(double deadband) { - if(minimumNominalOutput > 0) { - LogKitten.ex("Cannot set both PID deadband and minimum nominal output"); + if (minimumNominalOutput > 0) { + LogKitten.e("Removing minimum nominal output in favor of deadband"); } minimumNominalOutput = 0; this.deadband = deadband; } - /** - * Sets the threshold below which the I term becomes active. - * When the I term is active, the error sum increases. When - * the I term is not active, the error sum is set to zero. + * Sets the threshold below which the I term becomes active. When the I term + * is active, the error sum increases. When the I term is not active, the + * error sum is set to zero. * * @param integralThreshold */ @@ -266,9 +256,9 @@ public void setIThreshold(double integralThreshold) { } /** - * Gets the threshold below which the I term becomes active. - * When the I term is active, the error sum increases. When - * the I term is not active, the error sum is set to zero. + * Gets the threshold below which the I term becomes active. When the I term + * is active, the error sum increases. When the I term is not active, the + * error sum is set to zero. * * @return */ @@ -291,12 +281,12 @@ public double getError() { } /** - * Get the current output of the PID loop. - * This should be used to set the output (like a Motor). + * Get the current output of the PID loop. This should be used to set the + * output (like a Motor). * * @return The current output of the PID loop. * @throws InvalidSensorException - * when a sensor fails + * when a sensor fails */ @Override public double getSafely() throws InvalidSensorException { @@ -310,7 +300,8 @@ public double getSafely() throws InvalidSensorException { // Account for continuous input ranges if (continuous) { double range = inputMax - inputMin; - // If the error is more than half of the range, it is faster to increase the error and loop around the boundary + // If the error is more than half of the range, it is faster to + // increase the error and loop around the boundary if (Math.abs(error) > range / 2) { if (error > 0) { error -= range; @@ -322,18 +313,23 @@ public double getSafely() throws InvalidSensorException { long latestTime = System.currentTimeMillis(); long timeDiff = latestTime - lastTime; lastTime = latestTime; - // If we just reset, then the lastTime could be way before the latestTime and so timeDiff would be huge. + // If we just reset, then the lastTime could be way before the + // latestTime and so timeDiff would be huge. // This would lead to a very big I (and a big D, briefly). - // Also, D could be unpredictable because lastError could be wildly different than error (since they're + // Also, D could be unpredictable because lastError could be wildly + // different than error (since they're // separated by more than a tick in time). - // Hence, if we just reset, just pretend we're still disabled and record the lastTime and lastError for next tick. + // Hence, if we just reset, just pretend we're still disabled and record + // the lastTime and lastError for next tick. if (didJustReset()) { lastError = error; return F * setpoint; } double errorDerivative; - // Check if the sensor supports native derivative calculations and that we're doing displacement PID - // (if we're doing rate PID, then getRate() would be the PID input rather then the input's derivative) + // Check if the sensor supports native derivative calculations and that + // we're doing displacement PID + // (if we're doing rate PID, then getRate() would be the PID input + // rather then the input's derivative) if (sensor instanceof NativeDerivativeSensor && sensor.getPIDSourceType() == PIDSourceType.kDisplacement) { errorDerivative = ((NativeDerivativeSensor) sensor).getRateSafely(); } else { @@ -352,7 +348,8 @@ public double getSafely() throws InvalidSensorException { lastError = error; LogKitten.v(input + " " + setpoint + " " + result); if (capOutput) { - // Limit the result to be within the output range [outputMin, outputMax] + // Limit the result to be within the output range [outputMin, + // outputMax] result = Math.max(Math.min(result, outputMax), outputMin); } if (Math.abs(result) < minimumNominalOutput) { @@ -364,8 +361,8 @@ public double getSafely() throws InvalidSensorException { } /** - * Get the current output of the PID loop. - * This should be used to set the output (like a Motor). + * Get the current output of the PID loop. This should be used to set the + * output (like a Motor). * * @return The current output of the PID loop. * @warning does not indicate sensor error @@ -374,8 +371,7 @@ public double getSafely() throws InvalidSensorException { public double get() { try { return getSafely(); - } - catch (Exception e) { + } catch (Exception e) { LogKitten.ex(e); return 0; } From 2005d5ea25ba75a22c9830739e2284e35b2abc70 Mon Sep 17 00:00:00 2001 From: AJ Nadel Date: Fri, 24 Mar 2017 16:25:08 -0700 Subject: [PATCH 4/5] formatting fixes --- .../CustomPIDController.java | 171 +++++++++--------- 1 file changed, 85 insertions(+), 86 deletions(-) diff --git a/custom/motioncontrollers/CustomPIDController.java b/custom/motioncontrollers/CustomPIDController.java index 3256b391..8259959b 100644 --- a/custom/motioncontrollers/CustomPIDController.java +++ b/custom/motioncontrollers/CustomPIDController.java @@ -1,17 +1,17 @@ package org.usfirst.frc4904.standard.custom.motioncontrollers; + import org.usfirst.frc4904.standard.LogKitten; import org.usfirst.frc4904.standard.custom.sensors.InvalidSensorException; import org.usfirst.frc4904.standard.custom.sensors.NativeDerivativeSensor; import org.usfirst.frc4904.standard.custom.sensors.PIDSensor; - import edu.wpi.first.wpilibj.PIDSource; import edu.wpi.first.wpilibj.PIDSourceType; import edu.wpi.first.wpilibj.util.BoundaryException; /** - * An extremely basic PID controller. It does not differentiate between rate and - * distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * */ public class CustomPIDController extends MotionController { @@ -27,19 +27,19 @@ public class CustomPIDController extends MotionController { protected double deadband = 0.0; /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param F - * Initial F (feed forward) constant + * Initial F (feed forward) constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, double F, PIDSensor sensor) { super(sensor); @@ -50,19 +50,19 @@ public CustomPIDController(double P, double I, double D, double F, PIDSensor sen } /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param F - * Initial F (feed forward) constant + * Initial F (feed forward) constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, double F, PIDSource source) { super(source); @@ -73,100 +73,104 @@ public CustomPIDController(double P, double I, double D, double F, PIDSource sou } /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, PIDSensor sensor) { this(P, I, D, 0.0, sensor); } /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param P - * Initial P constant + * Initial P constant * @param I - * Initial I constant + * Initial I constant * @param D - * Initial D constant + * Initial D constant * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(double P, double I, double D, PIDSource source) { this(P, I, D, 0.0, source); } /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(PIDSensor sensor) { this(0, 0, 0, sensor); } /** - * An extremely basic PID controller. It does not differentiate between rate - * and distance. + * An extremely basic PID controller. + * It does not differentiate between rate and distance. * * @param sensor - * The sensor linked to the output + * The sensor linked to the output */ public CustomPIDController(PIDSource source) { this(0, 0, 0, source); } /** - * @return The current P value + * @return + * The current P value */ public double getP() { return P; } /** - * @return The current I value + * @return + * The current I value */ public double getI() { return I; } /** - * @return The current D value + * @return + * The current D value */ public double getD() { return D; } /** - * @return The current F (feed forward) value + * @return + * The current F (feed forward) value */ public double getF() { return F; } /** - * - * @return The current minimumNominalOutput (minimum nominal output) value + * @return + * The current minimumNominalOutput (minimum nominal output) value */ public double getMinimumNominalOutput() { return minimumNominalOutput; } /** - * - * @return The current deadband value + * @return + * The current deadband value */ public double getDeadband() { return deadband; @@ -176,14 +180,14 @@ public double getDeadband() { * Sets the parameters of the PID loop * * @param P - * Proportional + * Proportional * @param I - * Integral + * Integral * @param D - * Derivative + * Derivative * - * If you do not know what these mean, please refer to this link: - * https://en.wikipedia.org/wiki/PID_controller + * If you do not know what these mean, please refer + * to this link: https://en.wikipedia.org/wiki/PID_controller */ public void setPID(double P, double I, double D) { this.P = P; @@ -195,16 +199,16 @@ public void setPID(double P, double I, double D) { * Sets the parameters of the PID loop * * @param P - * Proportional + * Proportional * @param I - * Integral + * Integral * @param D - * Derivative + * Derivative * @param F - * Feed forward (scalar on input added to output) + * Feed forward (scalar on input added to output) * - * If you do not know what these mean, please refer to this link: - * https://en.wikipedia.org/wiki/PID_controller + * If you do not know what these mean, please refer + * to this link: https://en.wikipedia.org/wiki/PID_controller */ public void setPIDF(double P, double I, double D, double F) { this.P = P; @@ -214,11 +218,13 @@ public void setPIDF(double P, double I, double D, double F) { } /** - * * @param minimumNominalOutput - * Minimum Nominal Output result will be set to ±this value if - * the absolute value of the result is less than this value. This - * is useful if the motor can only run well above a value. + * Minimum Nominal Output + * result will be set to + * ±this value if the absolute + * value of the result is less than + * this value. This is useful if + * the motor can only run well above a value. */ public void setMinimumNominalOutput(double minimumNominalOutput) { if (deadband > 0) { @@ -229,9 +235,8 @@ public void setMinimumNominalOutput(double minimumNominalOutput) { } /** - * * @param deadband - * PID output will be set to 0 if it is lower than the deadband + * PID output will be set to 0 if it is lower than the deadband */ public void setDeadband(double deadband) { if (minimumNominalOutput > 0) { @@ -242,9 +247,9 @@ public void setDeadband(double deadband) { } /** - * Sets the threshold below which the I term becomes active. When the I term - * is active, the error sum increases. When the I term is not active, the - * error sum is set to zero. + * Sets the threshold below which the I term becomes active. + * When the I term is active, the error sum increases. When + * the I term is not active, the error sum is set to zero. * * @param integralThreshold */ @@ -256,9 +261,9 @@ public void setIThreshold(double integralThreshold) { } /** - * Gets the threshold below which the I term becomes active. When the I term - * is active, the error sum increases. When the I term is not active, the - * error sum is set to zero. + * Gets the threshold below which the I term becomes active. + * When the I term is active, the error sum increases. When + * the I term is not active, the error sum is set to zero. * * @return */ @@ -281,12 +286,12 @@ public double getError() { } /** - * Get the current output of the PID loop. This should be used to set the - * output (like a Motor). + * Get the current output of the PID loop. + * This should be used to set the output (like a Motor). * * @return The current output of the PID loop. * @throws InvalidSensorException - * when a sensor fails + * when a sensor fails */ @Override public double getSafely() throws InvalidSensorException { @@ -300,8 +305,7 @@ public double getSafely() throws InvalidSensorException { // Account for continuous input ranges if (continuous) { double range = inputMax - inputMin; - // If the error is more than half of the range, it is faster to - // increase the error and loop around the boundary + // If the error is more than half of the range, it is faster to increase the error and loop around the boundary if (Math.abs(error) > range / 2) { if (error > 0) { error -= range; @@ -313,23 +317,18 @@ public double getSafely() throws InvalidSensorException { long latestTime = System.currentTimeMillis(); long timeDiff = latestTime - lastTime; lastTime = latestTime; - // If we just reset, then the lastTime could be way before the - // latestTime and so timeDiff would be huge. + // If we just reset, then the lastTime could be way before the latestTime and so timeDiff would be huge. // This would lead to a very big I (and a big D, briefly). - // Also, D could be unpredictable because lastError could be wildly - // different than error (since they're + // Also, D could be unpredictable because lastError could be wildly different than error (since they're // separated by more than a tick in time). - // Hence, if we just reset, just pretend we're still disabled and record - // the lastTime and lastError for next tick. + // Hence, if we just reset, just pretend we're still disabled and record the lastTime and lastError for next tick. if (didJustReset()) { lastError = error; return F * setpoint; } double errorDerivative; - // Check if the sensor supports native derivative calculations and that - // we're doing displacement PID - // (if we're doing rate PID, then getRate() would be the PID input - // rather then the input's derivative) + // Check if the sensor supports native derivative calculations and that we're doing displacement PID + // (if we're doing rate PID, then getRate() would be the PID input rather then the input's derivative) if (sensor instanceof NativeDerivativeSensor && sensor.getPIDSourceType() == PIDSourceType.kDisplacement) { errorDerivative = ((NativeDerivativeSensor) sensor).getRateSafely(); } else { @@ -348,8 +347,7 @@ public double getSafely() throws InvalidSensorException { lastError = error; LogKitten.v(input + " " + setpoint + " " + result); if (capOutput) { - // Limit the result to be within the output range [outputMin, - // outputMax] + // Limit the result to be within the output range [outputMin, outputMax] result = Math.max(Math.min(result, outputMax), outputMin); } if (Math.abs(result) < minimumNominalOutput) { @@ -361,8 +359,8 @@ public double getSafely() throws InvalidSensorException { } /** - * Get the current output of the PID loop. This should be used to set the - * output (like a Motor). + * Get the current output of the PID loop. + * This should be used to set the output (like a Motor). * * @return The current output of the PID loop. * @warning does not indicate sensor error @@ -371,7 +369,8 @@ public double getSafely() throws InvalidSensorException { public double get() { try { return getSafely(); - } catch (Exception e) { + } + catch (Exception e) { LogKitten.ex(e); return 0; } From cacadd0a907600d86430dfa95f5afb021d98edf9 Mon Sep 17 00:00:00 2001 From: AJ Nadel Date: Fri, 24 Mar 2017 16:26:30 -0700 Subject: [PATCH 5/5] semantics: use level warn because nothing has broken --- custom/motioncontrollers/CustomPIDController.java | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/custom/motioncontrollers/CustomPIDController.java b/custom/motioncontrollers/CustomPIDController.java index 8259959b..af00918a 100644 --- a/custom/motioncontrollers/CustomPIDController.java +++ b/custom/motioncontrollers/CustomPIDController.java @@ -228,7 +228,7 @@ public void setPIDF(double P, double I, double D, double F) { */ public void setMinimumNominalOutput(double minimumNominalOutput) { if (deadband > 0) { - LogKitten.e("Removing deadband in favor of minimum nominal output"); + LogKitten.w("Removing deadband in favor of minimum nominal output"); } deadband = 0; this.minimumNominalOutput = minimumNominalOutput; @@ -240,7 +240,7 @@ public void setMinimumNominalOutput(double minimumNominalOutput) { */ public void setDeadband(double deadband) { if (minimumNominalOutput > 0) { - LogKitten.e("Removing minimum nominal output in favor of deadband"); + LogKitten.w("Removing minimum nominal output in favor of deadband"); } minimumNominalOutput = 0; this.deadband = deadband;