Package org.hyperonline.hyperlib.pid
Class PrefPIDController
- java.lang.Object
-
- edu.wpi.first.wpilibj.SendableBase
-
- edu.wpi.first.wpilibj.PIDBase
-
- edu.wpi.first.wpilibj.PIDController
-
- org.hyperonline.hyperlib.pid.PrefPIDController
-
- All Implemented Interfaces:
edu.wpi.first.wpilibj.Controller
,edu.wpi.first.wpilibj.PIDInterface
,edu.wpi.first.wpilibj.PIDOutput
,edu.wpi.first.wpilibj.Sendable
,java.lang.AutoCloseable
- Direct Known Subclasses:
PassivePIDController
public class PrefPIDController extends edu.wpi.first.wpilibj.PIDController
This class wraps aPIDController
, using the Preferences file to store and load parameters. The methods which set parameters only set defaults, and the Preferences file is always used if it is set. This allows for easy tuning of constants with persistent storage, without having to recompile the code.
-
-
Constructor Summary
Constructors Constructor Description PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, double Kf, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output)
PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, double Kf, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output, double period)
PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output)
PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output, double period)
-
Method Summary
All Methods Instance Methods Concrete Methods Deprecated Methods Modifier and Type Method Description double
getTolerance()
Gets the tolerance of the PIDboolean
isAbove(double target, boolean reverse)
Is the system above the given targetboolean
isBelow(double target, boolean reverse)
Is the system below the given targetvoid
setAbsoluteTolerance(double tolerance)
Set the default absolute tolerance.void
setOutputRange(double min, double max)
Set the default output range.void
setPercentTolerance(double tolerance)
Deprecated.void
setPID(double p, double i, double d)
Deprecated.void
setPID(double p, double i, double d, double f)
Deprecated.-
Methods inherited from class edu.wpi.first.wpilibj.PIDController
close, disable, enable, initSendable, isEnabled, reset, setEnabled
-
Methods inherited from class edu.wpi.first.wpilibj.PIDBase
calculate, calculateFeedForward, get, getAvgError, getContinuousError, getD, getDeltaSetpoint, getError, getF, getI, getP, getSetpoint, onTarget, pidWrite, setContinuous, setContinuous, setD, setF, setI, setInputRange, setP, setSetpoint, setTolerance, setToleranceBuffer
-
Methods inherited from class edu.wpi.first.wpilibj.SendableBase
addChild, free, getName, getSubsystem, setName, setName, setName, setSubsystem
-
-
-
-
Constructor Detail
-
PrefPIDController
public PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output)
- Parameters:
prefString
- A string to identify preferencesKp
- the default value for PKi
- the default value for IKd
- the default value for Dsource
- the source of feedbackoutput
- the output of the PID- See Also:
PIDController(double, double, double, PIDSource, PIDOutput)
-
PrefPIDController
public PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output, double period)
- Parameters:
prefString
- A string to identify preferencesKp
- the default value for PKi
- the default value for IKd
- the default value for Dsource
- the source of feedbackoutput
- the output of the PIDperiod
- the period to run the PID controller at- See Also:
PIDController(double, double, double, PIDSource, PIDOutput, double)
-
PrefPIDController
public PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, double Kf, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output)
- Parameters:
prefString
- A string to identify preferencesKp
- the default value for PKi
- the default value for IKd
- the default value for DKf
- the default value for Fsource
- the source of feedbackoutput
- the output of the PID- See Also:
PIDController(double, double, double, double, PIDSource, PIDOutput)
-
PrefPIDController
public PrefPIDController(java.lang.String prefString, double Kp, double Ki, double Kd, double Kf, edu.wpi.first.wpilibj.PIDSource source, edu.wpi.first.wpilibj.PIDOutput output, double period)
- Parameters:
prefString
- A string to identify preferencesKp
- the default value for PKi
- the default value for IKd
- the default value for DKf
- the default value for Fsource
- the source of feedbackoutput
- the output of the PIDperiod
- the period to run the PID controller at- See Also:
PIDController(double, double, double, double, PIDSource, PIDOutput, double)
-
-
Method Detail
-
setPID
@Deprecated public void setPID(double p, double i, double d, double f)
Deprecated.- Overrides:
setPID
in classedu.wpi.first.wpilibj.PIDBase
-
setPID
@Deprecated public void setPID(double p, double i, double d)
Deprecated.- Specified by:
setPID
in interfaceedu.wpi.first.wpilibj.PIDInterface
- Overrides:
setPID
in classedu.wpi.first.wpilibj.PIDBase
-
setPercentTolerance
@Deprecated public void setPercentTolerance(double tolerance)
Deprecated.- Overrides:
setPercentTolerance
in classedu.wpi.first.wpilibj.PIDBase
-
setAbsoluteTolerance
public void setAbsoluteTolerance(double tolerance)
Set the default absolute tolerance. In most cases it will only matter what you pass to this the first time you call it, since it will then add an entry to the preferences file if one does not yet exist.- Overrides:
setAbsoluteTolerance
in classedu.wpi.first.wpilibj.PIDBase
- Parameters:
tolerance
- The new default value for absolute tolerance.- See Also:
PIDBase.setAbsoluteTolerance(double)
-
setOutputRange
public void setOutputRange(double min, double max)
Set the default output range. In most cases it will only matter what you pass to this the first time you call it, since it will then add an entry to the preferences file if one does not yet exist.- Overrides:
setOutputRange
in classedu.wpi.first.wpilibj.PIDBase
- Parameters:
min
- The lower bound on the output. By default -1.max
- The upper bound on the output. By default 1.- See Also:
PIDBase.setOutputRange(double, double)
-
getTolerance
public double getTolerance()
Gets the tolerance of the PID- Returns:
- the tolerance of this PID
-
isAbove
public boolean isAbove(double target, boolean reverse)
Is the system above the given target- Parameters:
target
- setpoint to check if the PID system is abovereverse
- is the system reversed- Returns:
- is the system above the given target
-
isBelow
public boolean isBelow(double target, boolean reverse)
Is the system below the given target- Parameters:
target
- setpoint to check if the PID system is belowreverse
- is the system reversed- Returns:
- is the system below the given target
-
-