Class MiniPID

java.lang.Object
io.gitbub.devlibx.easy.helper.pid.MiniPID

public class MiniPID extends Object
  • Constructor Summary

    Constructors
    Constructor
    Description
    MiniPID(double p, double i, double d)
    Create a MiniPID class object.
    MiniPID(double p, double i, double d, double f)
    Create a MiniPID class object.
  • Method Summary

    Modifier and Type
    Method
    Description
    double
    Calculate the output value for the current PID cycle.
    In no-parameter mode, this uses the last sensor value, and last setpoint value.
    double
    getOutput(double actual)
    Calculate the output value for the current PID cycle.
    In one parameter mode, the last configured setpoint will be used.
    double
    getOutput(double actual, double setpoint)
    Calculate the output value for the current PID cycle.
    void
    Resets the controller.
    void
    setD(double d)
    Changes the D parameter
    This has two primary effects: Adds a "startup kick" and speeds up system response during setpoint changes Adds "drag" and slows the system when moving toward the target A small D value can be useful for both improving response times, and preventing overshoot.
    void
    setDirection(boolean reversed)
    Set the operating direction of the PID controller
    void
    setF(double f)
    Configure the FeedForward parameter.
    void
    setI(double i)
    Changes the I parameter
    This is used for overcoming disturbances, and ensuring that the controller always gets to the control mode.
    void
    setMaxIOutput(double maximum)
    Set the maximum output value contributed by the I component of the system This can be used to prevent large windup issues and make tuning simpler
    void
    setOutputFilter(double strength)
    Set a filter on the output to reduce sharp oscillations.
    void
    setOutputLimits(double output)
    Specify a maximum output range.
    void
    setOutputLimits(double minimum, double maximum)
    Specify a maximum output.
    void
    setOutputRampRate(double rate)
    Set the maximum rate the output can increase per cycle.
    This can prevent sharp jumps in output when changing setpoints or enabling a PID system, which might cause stress on physical or electrical systems.
    void
    setP(double p)
    Configure the Proportional gain parameter.
    void
    setPID(double p, double i, double d)
    Configure the PID object.
    void
    setPID(double p, double i, double d, double f)
    Configure the PID object.
    void
    setSetpoint(double setpoint)
    Configure setpoint for the PID calculations
    This represents the target for the PID system's, such as a position, velocity, or angle.
    void
    setSetpointRange(double range)
    Set a limit on how far the setpoint can be from the current position
    Can simplify tuning by helping tuning over a small range applies to a much larger range.

    Methods inherited from class java.lang.Object

    clone, equals, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Constructor Details

    • MiniPID

      public MiniPID(double p, double i, double d)
      Create a MiniPID class object. See setP, setI, setD methods for more detailed parameters.
      Parameters:
      p - Proportional gain. Large if large difference between setpoint and target.
      i - Integral gain. Becomes large if setpoint cannot reach target quickly.
      d - Derivative gain. Responds quickly to large changes in error. Small values prevents P and I terms from causing overshoot.
    • MiniPID

      public MiniPID(double p, double i, double d, double f)
      Create a MiniPID class object. See setP, setI, setD, setF methods for more detailed parameters.
      Parameters:
      p - Proportional gain. Large if large difference between setpoint and target.
      i - Integral gain. Becomes large if setpoint cannot reach target quickly.
      d - Derivative gain. Responds quickly to large changes in error. Small values prevents P and I terms from causing overshoot.
      f - Feed-forward gain. Open loop "best guess" for the output should be. Only useful if setpoint represents a rate.
  • Method Details

    • setP

      public void setP(double p)
      Configure the Proportional gain parameter.
      This responds quickly to changes in setpoint, and provides most of the initial driving force to make corrections.
      Some systems can be used with only a P gain, and many can be operated with only PI.
      For position based controllers, this is the first parameter to tune, with I second.
      For rate controlled systems, this is often the second after F.
      Parameters:
      p - Proportional gain. Affects output according to output+=P*(setpoint-current_value)
    • setI

      public void setI(double i)
      Changes the I parameter
      This is used for overcoming disturbances, and ensuring that the controller always gets to the control mode. Typically tuned second for "Position" based modes, and third for "Rate" or continuous based modes.
      Affects output through output+=previous_errors*Igain ;previous_errors+=current_error
      Parameters:
      i - New gain value for the Integral term
    • setD

      public void setD(double d)
      Changes the D parameter
      This has two primary effects:
    • Adds a "startup kick" and speeds up system response during setpoint changes
    • Adds "drag" and slows the system when moving toward the target A small D value can be useful for both improving response times, and preventing overshoot. However, in many systems a large D value will cause significant instability, particularly for large setpoint changes.
      Affects output through output += -D*(current_input_value - last_input_value)
    • Parameters:
      d - New gain value for the Derivative term
    • setF

      public void setF(double f)
      Configure the FeedForward parameter.
      This is excellent for velocity, rate, and other continuous control modes where you can expect a rough output value based solely on the setpoint.
      Should not be used in "position" based control modes.
      Affects output according to output+=F*Setpoint. Note, that a F-only system is actually open loop.
      Parameters:
      f - Feed forward gain.
    • setPID

      public void setPID(double p, double i, double d)
      Configure the PID object. See setP, setI, setD methods for more detailed parameters.
      Parameters:
      p - Proportional gain. Large if large difference between setpoint and target.
      i - Integral gain. Becomes large if setpoint cannot reach target quickly.
      d - Derivative gain. Responds quickly to large changes in error. Small values prevents P and I terms from causing overshoot.
    • setPID

      public void setPID(double p, double i, double d, double f)
      Configure the PID object. See setP, setI, setD, setF methods for more detailed parameters.
      Parameters:
      p - Proportional gain. Large if large difference between setpoint and target.
      i - Integral gain. Becomes large if setpoint cannot reach target quickly.
      d - Derivative gain. Responds quickly to large changes in error. Small values prevents P and I terms from causing overshoot.
      f - Feed-forward gain. Open loop "best guess" for the output should be. Only useful if setpoint represents a rate.
    • setMaxIOutput

      public void setMaxIOutput(double maximum)
      Set the maximum output value contributed by the I component of the system This can be used to prevent large windup issues and make tuning simpler
      Parameters:
      maximum - . Units are the same as the expected output value
    • setOutputLimits

      public void setOutputLimits(double output)
      Specify a maximum output range.
      When one input is specified, output range is configured to [-output, output]
      Parameters:
      output -
    • setOutputLimits

      public void setOutputLimits(double minimum, double maximum)
      Specify a maximum output. When two inputs specified, output range is configured to [minimum, maximum]
      Parameters:
      minimum - possible output value
      maximum - possible output value
    • setDirection

      public void setDirection(boolean reversed)
      Set the operating direction of the PID controller
      Parameters:
      reversed - Set true to reverse PID output
    • setSetpoint

      public void setSetpoint(double setpoint)
      Configure setpoint for the PID calculations
      This represents the target for the PID system's, such as a position, velocity, or angle.
      Parameters:
      setpoint -
      See Also:

    • getOutput

      public double getOutput(double actual, double setpoint)
      Calculate the output value for the current PID cycle.
      Parameters:
      actual - The monitored value, typically as a sensor input.
      setpoint - The target value for the system
      Returns:
      calculated output value for driving the system
    • getOutput

      public double getOutput()
      Calculate the output value for the current PID cycle.
      In no-parameter mode, this uses the last sensor value, and last setpoint value.
      Not typically useful, and use of parameter modes is suggested.
      Returns:
      calculated output value for driving the system
    • getOutput

      public double getOutput(double actual)
      Calculate the output value for the current PID cycle.
      In one parameter mode, the last configured setpoint will be used.
      Parameters:
      actual - The monitored value, typically as a sensor input.
      setpoint - The target value for the system
      Returns:
      calculated output value for driving the system
      See Also:
      • invalid @see
        MiniPID#setSetpoint()
    • reset

      public void reset()
      Resets the controller. This erases the I term buildup, and removes D gain on the next loop.
      This should be used any time the PID is disabled or inactive for extended duration, and the controlled portion of the system may have changed due to external forces.
    • setOutputRampRate

      public void setOutputRampRate(double rate)
      Set the maximum rate the output can increase per cycle.
      This can prevent sharp jumps in output when changing setpoints or enabling a PID system, which might cause stress on physical or electrical systems.
      Can be very useful for fast-reacting control loops, such as ones with large P or D values and feed-forward systems.
      Parameters:
      rate - , with units being the same as the output
    • setSetpointRange

      public void setSetpointRange(double range)
      Set a limit on how far the setpoint can be from the current position
      Can simplify tuning by helping tuning over a small range applies to a much larger range.
      This limits the reactivity of P term, and restricts impact of large D term during large setpoint adjustments. Increases lag and I term if range is too small.
      Parameters:
      range - , with units being the same as the expected sensor range.
    • setOutputFilter

      public void setOutputFilter(double strength)
      Set a filter on the output to reduce sharp oscillations.
      0.1 is likely a sane starting value. Larger values use historical data more heavily, with low values weigh newer data. 0 will disable, filtering, and use only the most recent value.
      Increasing the filter strength will P and D oscillations, but force larger I values and increase I term overshoot.
      Uses an exponential wieghted rolling sum filter, according to a simple
      output*(1-strength)*sum(0..n){output*strength^n}
      algorithm.
      Parameters:
      output - valid between [0..1), meaning [current output only.. historical output only)