13 #include <support/deprecated.h> 14 #include <support/mutex.h> 17 #include "Controller.h" 18 #include "Filters/LinearDigitalFilter.h" 20 #include "PIDInterface.h" 21 #include "PIDSource.h" 22 #include "SmartDashboard/SendableBase.h" 54 virtual double Get()
const;
56 virtual void SetInputRange(
double minimumInput,
double maximumInput);
57 virtual void SetOutputRange(
double minimumOutput,
double maximumOutput);
58 void SetPID(
double p,
double i,
double d)
override;
59 virtual void SetPID(
double p,
double i,
double d,
double f);
64 double GetP()
const override;
65 double GetI()
const override;
66 double GetD()
const override;
67 virtual double GetF()
const;
75 WPI_DEPRECATED(
"Use a LinearDigitalFilter as the input and GetError().")
81 WPI_DEPRECATED(
"Use SetPercentTolerance() instead.")
82 virtual void SetTolerance(
double percent);
83 virtual void SetAbsoluteTolerance(
double absValue);
84 virtual void SetPercentTolerance(
double percentValue);
86 WPI_DEPRECATED(
"Use a LinearDigitalFilter as the input.")
87 virtual void SetToleranceBuffer(
int buf = 1);
89 virtual bool OnTarget()
const;
96 void Reset()
override;
122 double m_maximumOutput = 1.0;
125 double m_minimumOutput = -1.0;
128 double m_maximumInput = 0;
131 double m_minimumInput = 0;
134 double m_inputRange = 0;
137 bool m_continuous =
false;
140 bool m_enabled =
false;
143 double m_prevError = 0;
146 double m_totalError = 0;
152 } m_toleranceType = kNoTolerance;
155 double m_tolerance = 0.05;
157 double m_setpoint = 0;
158 double m_prevSetpoint = 0;
163 std::shared_ptr<PIDSource> m_origSource;
166 mutable wpi::mutex m_thisMutex;
170 mutable wpi::mutex m_pidWriteMutex;
172 std::unique_ptr<Notifier> m_controlLoop;
173 Timer m_setpointTimer;
virtual void SetInputRange(double minimumInput, double maximumInput)
Sets the maximum and minimum values expected from the input.
Definition: PIDController.cpp:387
virtual double Get() const
Return the current PID result.
Definition: PIDController.cpp:362
Definition: RobotController.cpp:14
double GetD() const override
Get the Differential coefficient.
Definition: PIDController.cpp:340
void SetD(double d)
Set the Differential coefficient of the PID controller gain.
Definition: PIDController.cpp:300
virtual void SetPIDSourceType(PIDSourceType pidSource)
Sets what type of input the PID controller will use.
Definition: PIDController.cpp:478
virtual double GetAvgError() const
Returns the current average of the error over the past few iterations.
Definition: PIDController.cpp:473
virtual void SetContinuous(bool continuous=true)
Set the PID controller to consider the input to be continuous,.
Definition: PIDController.cpp:376
virtual PIDSourceType GetPIDSourceType() const
Returns the type of input the PID controller is using.
Definition: PIDController.cpp:486
PIDSource interface is a generic sensor source for the PID class.
Definition: PIDSource.h:20
Class implements a PID Control Loop.
Definition: PIDController.h:39
void InitSendable(SendableBuilder &builder) override
Initializes this Sendable object.
Definition: PIDController.cpp:630
virtual double CalculateFeedForward()
Calculate the feed forward term.
Definition: PIDController.cpp:228
PIDOutput interface is a generic output for the PID class.
Definition: PIDOutput.h:20
double GetDeltaSetpoint() const
Returns the change in setpoint over time of the PIDController.
Definition: PIDController.cpp:447
virtual double GetF() const
Get the Feed forward coefficient.
Definition: PIDController.cpp:350
Timer objects measure accumulated time in seconds.
Definition: Timer.h:33
double GetContinuousError(double error) const
Wraps error around for continuous inputs.
Definition: PIDController.cpp:654
void SetF(double f)
Get the Feed forward coefficient of the PID controller gain.
Definition: PIDController.cpp:310
double GetP() const override
Get the Proportional coefficient.
Definition: PIDController.cpp:320
virtual double GetError() const
Returns the current difference of the input from the setpoint.
Definition: PIDController.cpp:457
void Reset() override
Reset the previous error, the integral term, and disable the controller.
Definition: PIDController.cpp:621
bool IsEnabled() const override
Return true if PIDController is enabled.
Definition: PIDController.cpp:613
Definition: PIDInterface.h:15
void SetPID(double p, double i, double d) override
Set the PID Controller gain parameters.
Definition: PIDController.cpp:248
double GetSetpoint() const override
Returns the current setpoint of the PIDController.
Definition: PIDController.cpp:437
Definition: SendableBase.h:19
virtual void SetOutputRange(double minimumOutput, double maximumOutput)
Sets the minimum and maximum values to write.
Definition: PIDController.cpp:404
double GetI() const override
Get the Integral coefficient.
Definition: PIDController.cpp:330
Definition: SendableBuilder.h:23
void SetP(double p)
Set the Proportional coefficient of the PID controller gain.
Definition: PIDController.cpp:280
void SetEnabled(bool enable)
Set the enabled state of the PIDController.
Definition: PIDController.cpp:602
This class implements a linear, digital filter.
Definition: LinearDigitalFilter.h:70
void SetSetpoint(double setpoint) override
Set the setpoint for the PIDController.
Definition: PIDController.cpp:415
PIDController(double p, double i, double d, PIDSource *source, PIDOutput *output, double period=0.05)
Allocate a PID object with the given constants for P, I, D.
Definition: PIDController.cpp:40
virtual void Calculate()
Read the input, calculate the output accordingly, and write to the output.
Definition: PIDController.cpp:128
void SetI(double i)
Set the Integral coefficient of the PID controller gain.
Definition: PIDController.cpp:290
void Disable() override
Stop running the PIDController, this sets the output to zero before stopping.
Definition: PIDController.cpp:586
void Enable() override
Begin running the PIDController.
Definition: PIDController.cpp:576