Class PIDFConfig

java.lang.Object
swervelib.parser.PIDFConfig

public class PIDFConfig extends Object
Hold the PIDF and Integral Zone values for a PID.
  • Field Summary

    Fields
    Modifier and Type
    Field
    Description
    double
    Derivative Gain for PID.
    double
    Feedforward value for PID.
    double
    Integral Gain for PID.
    double
    Integral zone of the PID.
    The PIDF output range.
    double
    Proportional Gain for PID.
  • Constructor Summary

    Constructors
    Constructor
    Description
    Used when parsing PIDF values from JSON.
    PIDFConfig(double p, double d)
    PIDF Config constructor to contain the values.
    PIDFConfig(double p, double i, double d)
    PIDF Config constructor to contain the values.
    PIDFConfig(double p, double i, double d, double f)
    PIDF Config constructor to contain the values.
    PIDFConfig(double p, double i, double d, double f, double iz)
    PIDF Config constructor to contain the values.
  • Method Summary

    Modifier and Type
    Method
    Description
    Create a PIDController from the PID values.

    Methods inherited from class java.lang.Object

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

    • p

      public double p
      Proportional Gain for PID.
    • i

      public double i
      Integral Gain for PID.
    • d

      public double d
      Derivative Gain for PID.
    • f

      public double f
      Feedforward value for PID.
    • iz

      public double iz
      Integral zone of the PID.
    • output

      public PIDFRange output
      The PIDF output range.
  • Constructor Details

    • PIDFConfig

      public PIDFConfig()
      Used when parsing PIDF values from JSON.
    • PIDFConfig

      public PIDFConfig(double p, double i, double d, double f, double iz)
      PIDF Config constructor to contain the values.
      Parameters:
      p - P gain.
      i - I gain.
      d - D gain.
      f - F gain.
      iz - Intergral zone.
    • PIDFConfig

      public PIDFConfig(double p, double i, double d, double f)
      PIDF Config constructor to contain the values.
      Parameters:
      p - P gain.
      i - I gain.
      d - D gain.
      f - F gain.
    • PIDFConfig

      public PIDFConfig(double p, double i, double d)
      PIDF Config constructor to contain the values.
      Parameters:
      p - P gain.
      i - I gain.
      d - D gain.
    • PIDFConfig

      public PIDFConfig(double p, double d)
      PIDF Config constructor to contain the values.
      Parameters:
      p - P gain.
      d - D gain.
  • Method Details

    • createPIDController

      public PIDController createPIDController()
      Create a PIDController from the PID values.
      Returns:
      PIDController.