Class 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 d
      Derivative Gain for PID.
      double f
      Feedforward value for PID.
      double i
      Integral Gain for PID.
      double iz
      Integral zone of the PID.
      PIDFRange output
      The PIDF output range.
      double p
      Proportional Gain for PID.
    • Constructor Summary

      Constructors 
      Constructor Description
      PIDFConfig()
      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.
    • Field Detail

      • 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 Detail

      • 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 Detail

      • createPIDController

        public edu.wpi.first.math.controller.PIDController createPIDController()
        Create a PIDController from the PID values.
        Returns:
        PIDController.