WPILibC++ 2024.1.1-beta-4
frc::PIDController Class Reference

Implements a PID control loop. More...

#include <frc/controller/PIDController.h>

Inheritance diagram for frc::PIDController:
wpi::Sendable wpi::SendableHelper< PIDController >

Public Member Functions

 PIDController (double Kp, double Ki, double Kd, units::second_t period=20_ms)
 Allocates a PIDController with the given constants for Kp, Ki, and Kd. More...
 
 ~PIDController () override=default
 
 PIDController (const PIDController &)=default
 
PIDControlleroperator= (const PIDController &)=default
 
 PIDController (PIDController &&)=default
 
PIDControlleroperator= (PIDController &&)=default
 
void SetPID (double Kp, double Ki, double Kd)
 Sets the PID Controller gain parameters. More...
 
void SetP (double Kp)
 Sets the proportional coefficient of the PID controller gain. More...
 
void SetI (double Ki)
 Sets the integral coefficient of the PID controller gain. More...
 
void SetD (double Kd)
 Sets the differential coefficient of the PID controller gain. More...
 
void SetIZone (double iZone)
 Sets the IZone range. More...
 
double GetP () const
 Gets the proportional coefficient. More...
 
double GetI () const
 Gets the integral coefficient. More...
 
double GetD () const
 Gets the differential coefficient. More...
 
double GetIZone () const
 Get the IZone range. More...
 
units::second_t GetPeriod () const
 Gets the period of this controller. More...
 
double GetPositionTolerance () const
 Gets the position tolerance of this controller. More...
 
double GetVelocityTolerance () const
 Gets the velocity tolerance of this controller. More...
 
void SetSetpoint (double setpoint)
 Sets the setpoint for the PIDController. More...
 
double GetSetpoint () const
 Returns the current setpoint of the PIDController. More...
 
bool AtSetpoint () const
 Returns true if the error is within the tolerance of the setpoint. More...
 
void EnableContinuousInput (double minimumInput, double maximumInput)
 Enables continuous input. More...
 
void DisableContinuousInput ()
 Disables continuous input. More...
 
bool IsContinuousInputEnabled () const
 Returns true if continuous input is enabled. More...
 
void SetIntegratorRange (double minimumIntegral, double maximumIntegral)
 Sets the minimum and maximum values for the integrator. More...
 
void SetTolerance (double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
 Sets the error which is considered tolerable for use with AtSetpoint(). More...
 
double GetPositionError () const
 Returns the difference between the setpoint and the measurement. More...
 
double GetVelocityError () const
 Returns the velocity error. More...
 
double Calculate (double measurement)
 Returns the next output of the PID controller. More...
 
double Calculate (double measurement, double setpoint)
 Returns the next output of the PID controller. More...
 
void Reset ()
 Reset the previous error, the integral term, and disable the controller. More...
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::Sendable
virtual ~Sendable ()=default
 
virtual void InitSendable (SendableBuilder &builder)=0
 Initializes this Sendable object. More...
 
- Public Member Functions inherited from wpi::SendableHelper< PIDController >
 SendableHelper (const SendableHelper &rhs)=default
 
 SendableHelper (SendableHelper &&rhs)
 
SendableHelperoperator= (const SendableHelper &rhs)=default
 
SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< PIDController >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Detailed Description

Implements a PID control loop.

Constructor & Destructor Documentation

◆ PIDController() [1/3]

frc::PIDController::PIDController ( double  Kp,
double  Ki,
double  Kd,
units::second_t  period = 20_ms 
)

Allocates a PIDController with the given constants for Kp, Ki, and Kd.

Parameters
KpThe proportional coefficient.
KiThe integral coefficient.
KdThe derivative coefficient.
periodThe period between controller updates in seconds. The default is 20 milliseconds. Must be non-zero and positive.

◆ ~PIDController()

frc::PIDController::~PIDController ( )
overridedefault

◆ PIDController() [2/3]

frc::PIDController::PIDController ( const PIDController )
default

◆ PIDController() [3/3]

frc::PIDController::PIDController ( PIDController &&  )
default

Member Function Documentation

◆ AtSetpoint()

bool frc::PIDController::AtSetpoint ( ) const

Returns true if the error is within the tolerance of the setpoint.

This will return false until at least one input value has been computed.

◆ Calculate() [1/2]

double frc::PIDController::Calculate ( double  measurement)

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.

◆ Calculate() [2/2]

double frc::PIDController::Calculate ( double  measurement,
double  setpoint 
)

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
setpointThe new setpoint of the controller.

◆ DisableContinuousInput()

void frc::PIDController::DisableContinuousInput ( )

Disables continuous input.

◆ EnableContinuousInput()

void frc::PIDController::EnableContinuousInput ( double  minimumInput,
double  maximumInput 
)

Enables continuous input.

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

Parameters
minimumInputThe minimum value expected from the input.
maximumInputThe maximum value expected from the input.

◆ GetD()

double frc::PIDController::GetD ( ) const

Gets the differential coefficient.

Returns
differential coefficient

◆ GetI()

double frc::PIDController::GetI ( ) const

Gets the integral coefficient.

Returns
integral coefficient

◆ GetIZone()

double frc::PIDController::GetIZone ( ) const

Get the IZone range.

Returns
Maximum magnitude of error to allow integral control.

◆ GetP()

double frc::PIDController::GetP ( ) const

Gets the proportional coefficient.

Returns
proportional coefficient

◆ GetPeriod()

units::second_t frc::PIDController::GetPeriod ( ) const

Gets the period of this controller.

Returns
The period of the controller.

◆ GetPositionError()

double frc::PIDController::GetPositionError ( ) const

Returns the difference between the setpoint and the measurement.

◆ GetPositionTolerance()

double frc::PIDController::GetPositionTolerance ( ) const

Gets the position tolerance of this controller.

Returns
The position tolerance of the controller.

◆ GetSetpoint()

double frc::PIDController::GetSetpoint ( ) const

Returns the current setpoint of the PIDController.

Returns
The current setpoint.

◆ GetVelocityError()

double frc::PIDController::GetVelocityError ( ) const

Returns the velocity error.

◆ GetVelocityTolerance()

double frc::PIDController::GetVelocityTolerance ( ) const

Gets the velocity tolerance of this controller.

Returns
The velocity tolerance of the controller.

◆ InitSendable()

void frc::PIDController::InitSendable ( wpi::SendableBuilder builder)
overridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ IsContinuousInputEnabled()

bool frc::PIDController::IsContinuousInputEnabled ( ) const

Returns true if continuous input is enabled.

◆ operator=() [1/2]

PIDController & frc::PIDController::operator= ( const PIDController )
default

◆ operator=() [2/2]

PIDController & frc::PIDController::operator= ( PIDController &&  )
default

◆ Reset()

void frc::PIDController::Reset ( )

Reset the previous error, the integral term, and disable the controller.

◆ SetD()

void frc::PIDController::SetD ( double  Kd)

Sets the differential coefficient of the PID controller gain.

Parameters
Kddifferential coefficient

◆ SetI()

void frc::PIDController::SetI ( double  Ki)

Sets the integral coefficient of the PID controller gain.

Parameters
Kiintegral coefficient

◆ SetIntegratorRange()

void frc::PIDController::SetIntegratorRange ( double  minimumIntegral,
double  maximumIntegral 
)

Sets the minimum and maximum values for the integrator.

When the cap is reached, the integrator value is added to the controller output rather than the integrator value times the integral gain.

Parameters
minimumIntegralThe minimum value of the integrator.
maximumIntegralThe maximum value of the integrator.

◆ SetIZone()

void frc::PIDController::SetIZone ( double  iZone)

Sets the IZone range.

When the absolute value of the position error is greater than IZone, the total accumulated error will reset to zero, disabling integral gain until the absolute value of the position error is less than IZone. This is used to prevent integral windup. Must be non-negative. Passing a value of zero will effectively disable integral gain. Passing a value of infinity disables IZone functionality.

Parameters
iZoneMaximum magnitude of error to allow integral control.

◆ SetP()

void frc::PIDController::SetP ( double  Kp)

Sets the proportional coefficient of the PID controller gain.

Parameters
Kpproportional coefficient

◆ SetPID()

void frc::PIDController::SetPID ( double  Kp,
double  Ki,
double  Kd 
)

Sets the PID Controller gain parameters.

Sets the proportional, integral, and differential coefficients.

Parameters
KpProportional coefficient
KiIntegral coefficient
KdDifferential coefficient

◆ SetSetpoint()

void frc::PIDController::SetSetpoint ( double  setpoint)

Sets the setpoint for the PIDController.

Parameters
setpointThe desired setpoint.

◆ SetTolerance()

void frc::PIDController::SetTolerance ( double  positionTolerance,
double  velocityTolerance = std::numeric_limits< double >::infinity() 
)

Sets the error which is considered tolerable for use with AtSetpoint().

Parameters
positionTolerancePosition error which is tolerable.
velocityToleranceVelocity error which is tolerable.

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