WPILibC++  unspecified
 All Classes Files Functions Variables Typedefs Enumerations Enumerator Pages
frc::PIDController Class Reference

Class implements a PID Control Loop. More...

#include <PIDController.h>

Inheritance diagram for frc::PIDController:
frc::LiveWindowSendable frc::PIDInterface ITableListener frc::Sendable frc::Controller

Public Member Functions

 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. More...
 
 PIDController (double p, double i, double d, double f, PIDSource *source, PIDOutput *output, double period=0.05)
 Allocate a PID object with the given constants for P, I, D. More...
 
 PIDController (const PIDController &)=delete
 
PIDControlleroperator= (const PIDController)=delete
 
virtual double Get () const
 Return the current PID result. More...
 
virtual void SetContinuous (bool continuous=true)
 Set the PID controller to consider the input to be continuous,. More...
 
virtual void SetInputRange (double minimumInput, double maximumInput)
 Sets the maximum and minimum values expected from the input. More...
 
virtual void SetOutputRange (double minimumOutput, double maximumOutput)
 Sets the minimum and maximum values to write. More...
 
void SetPID (double p, double i, double d) override
 Set the PID Controller gain parameters. More...
 
virtual void SetPID (double p, double i, double d, double f)
 Set the PID Controller gain parameters. More...
 
double GetP () const override
 Get the Proportional coefficient. More...
 
double GetI () const override
 Get the Integral coefficient. More...
 
double GetD () const override
 Get the Differential coefficient. More...
 
virtual double GetF () const
 Get the Feed forward coefficient. More...
 
void SetSetpoint (double setpoint) override
 Set the setpoint for the PIDController. More...
 
double GetSetpoint () const override
 Returns the current setpoint of the PIDController. More...
 
double GetDeltaSetpoint () const
 Returns the change in setpoint over time of the PIDController. More...
 
virtual double GetError () const
 Returns the current difference of the input from the setpoint. More...
 
virtual double GetAvgError () const
 Returns the current average of the error over the past few iterations. More...
 
virtual void SetPIDSourceType (PIDSourceType pidSource)
 Sets what type of input the PID controller will use.
 
virtual PIDSourceType GetPIDSourceType () const
 Returns the type of input the PID controller is using. More...
 
virtual void SetTolerance (double percent)
 
virtual void SetAbsoluteTolerance (double absValue)
 
virtual void SetPercentTolerance (double percentValue)
 
virtual void SetToleranceBuffer (int buf=1)
 
virtual bool OnTarget () const
 
void Enable () override
 Begin running the PIDController.
 
void Disable () override
 Stop running the PIDController, this sets the output to zero before stopping.
 
bool IsEnabled () const override
 Return true if PIDController is enabled.
 
void Reset () override
 Reset the previous error, the integral term, and disable the controller.
 
void InitTable (std::shared_ptr< ITable > subtable) override
 Initializes a table for this sendable object. More...
 
- Public Member Functions inherited from ITableListener
virtual void ValueChangedEx (ITable *source, llvm::StringRef key, std::shared_ptr< nt::Value > value, unsigned int flags)
 Extended version of ValueChanged. More...
 

Protected Member Functions

virtual void Calculate ()
 Read the input, calculate the output accordingly, and write to the output. More...
 
virtual double CalculateFeedForward ()
 Calculate the feed forward term. More...
 
double GetContinuousError (double error) const
 Wraps error around for continuous inputs. More...
 

Protected Attributes

PIDSourcem_pidInput
 
PIDOutputm_pidOutput
 
std::shared_ptr< ITablem_table
 

Detailed Description

Class implements a PID Control Loop.

Creates a separate thread which reads the given PIDSource and takes care of the integral calculations, as well as writing the given PIDOutput.

This feedback controller runs in discrete time, so time deltas are not used in the integral and derivative calculations. Therefore, the sample rate affects the controller's behavior for a given set of PID constants.

Constructor & Destructor Documentation

PIDController::PIDController ( double  Kp,
double  Ki,
double  Kd,
PIDSource source,
PIDOutput output,
double  period = 0.05 
)

Allocate a PID object with the given constants for P, I, D.

Parameters
Kpthe proportional coefficient
Kithe integral coefficient
Kdthe derivative coefficient
sourceThe PIDSource object that is used to get values
outputThe PIDOutput object that is set to the output value
periodthe loop time for doing calculations. This particularly effects calculations of the integral and differental terms. The default is 50ms.
PIDController::PIDController ( double  Kp,
double  Ki,
double  Kd,
double  Kf,
PIDSource source,
PIDOutput output,
double  period = 0.05 
)

Allocate a PID object with the given constants for P, I, D.

Parameters
Kpthe proportional coefficient
Kithe integral coefficient
Kdthe derivative coefficient
sourceThe PIDSource object that is used to get values
outputThe PIDOutput object that is set to the output value
periodthe loop time for doing calculations. This particularly effects calculations of the integral and differental terms. The default is 50ms.

Member Function Documentation

void PIDController::Calculate ( )
protectedvirtual

Read the input, calculate the output accordingly, and write to the output.

This should only be called by the Notifier.

double PIDController::CalculateFeedForward ( )
protectedvirtual

Calculate the feed forward term.

Both of the provided feed forward calculations are velocity feed forwards. If a different feed forward calculation is desired, the user can override this function and provide his or her own. This function does no synchronization because the PIDController class only calls it in synchronized code, so be careful if calling it oneself.

If a velocity PID controller is being used, the F term should be set to 1 over the maximum setpoint for the output. If a position PID controller is being used, the F term should be set to 1 over the maximum speed for the output measured in setpoint units per this controller's update period (see the default period in this class's constructor).

double PIDController::Get ( ) const
virtual

Return the current PID result.

This is always centered on zero and constrained the the max and min outs.

Returns
the latest calculated output
double PIDController::GetAvgError ( ) const
virtual

Returns the current average of the error over the past few iterations.

You can specify the number of iterations to average with SetToleranceBuffer() (defaults to 1). This is the same value that is used for OnTarget().

Returns
the average error
double PIDController::GetContinuousError ( double  error) const
protected

Wraps error around for continuous inputs.

The original error is returned if continuous mode is disabled. This is an unsynchronized function.

Parameters
errorThe current error of the PID controller.
Returns
Error for continuous inputs.
double PIDController::GetD ( ) const
overridevirtual

Get the Differential coefficient.

Returns
differential coefficient

Implements frc::PIDInterface.

double PIDController::GetDeltaSetpoint ( ) const

Returns the change in setpoint over time of the PIDController.

Returns
the change in setpoint over time
double PIDController::GetError ( ) const
virtual

Returns the current difference of the input from the setpoint.

Returns
the current error
double PIDController::GetF ( ) const
virtual

Get the Feed forward coefficient.

Returns
Feed forward coefficient
double PIDController::GetI ( ) const
overridevirtual

Get the Integral coefficient.

Returns
integral coefficient

Implements frc::PIDInterface.

double PIDController::GetP ( ) const
overridevirtual

Get the Proportional coefficient.

Returns
proportional coefficient

Implements frc::PIDInterface.

PIDSourceType PIDController::GetPIDSourceType ( ) const
virtual

Returns the type of input the PID controller is using.

Returns
the PID controller input type
double PIDController::GetSetpoint ( ) const
overridevirtual

Returns the current setpoint of the PIDController.

Returns
the current setpoint

Implements frc::PIDInterface.

void PIDController::InitTable ( std::shared_ptr< ITable subtable)
overridevirtual

Initializes a table for this sendable object.

Parameters
subtableThe table to put the values in.

Implements frc::Sendable.

void PIDController::SetContinuous ( bool  continuous = true)
virtual

Set the PID controller to consider the input to be continuous,.

Rather then using the max and min in as constraints, it considers them to be the same point and automatically calculates the shortest route to the setpoint.

Parameters
continuoustrue turns on continuous, false turns off continuous
void PIDController::SetInputRange ( double  minimumInput,
double  maximumInput 
)
virtual

Sets the maximum and minimum values expected from the input.

Parameters
minimumInputthe minimum value expected from the input
maximumInputthe maximum value expected from the output
void PIDController::SetOutputRange ( double  minimumOutput,
double  maximumOutput 
)
virtual

Sets the minimum and maximum values to write.

Parameters
minimumOutputthe minimum value to write to the output
maximumOutputthe maximum value to write to the output
void PIDController::SetPID ( double  p,
double  i,
double  d 
)
overridevirtual

Set the PID Controller gain parameters.

Set the proportional, integral, and differential coefficients.

Parameters
pProportional coefficient
iIntegral coefficient
dDifferential coefficient

Implements frc::PIDInterface.

void PIDController::SetPID ( double  p,
double  i,
double  d,
double  f 
)
virtual

Set the PID Controller gain parameters.

Set the proportional, integral, and differential coefficients.

Parameters
pProportional coefficient
iIntegral coefficient
dDifferential coefficient
fFeed forward coefficient
void PIDController::SetSetpoint ( double  setpoint)
overridevirtual

Set the setpoint for the PIDController.

Clears the queue for GetAvgError().

Parameters
setpointthe desired setpoint

Implements frc::PIDInterface.


The documentation for this class was generated from the following files: