WPILibC++ 2025.2.1
Loading...
Searching...
No Matches
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

constexpr 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.
 
constexpr ~PIDController () override=default
 
constexpr PIDController (const PIDController &)=default
 
constexpr PIDControlleroperator= (const PIDController &)=default
 
constexpr PIDController (PIDController &&)=default
 
constexpr PIDControlleroperator= (PIDController &&)=default
 
constexpr void SetPID (double Kp, double Ki, double Kd)
 Sets the PID Controller gain parameters.
 
constexpr void SetP (double Kp)
 Sets the proportional coefficient of the PID controller gain.
 
constexpr void SetI (double Ki)
 Sets the integral coefficient of the PID controller gain.
 
constexpr void SetD (double Kd)
 Sets the differential coefficient of the PID controller gain.
 
constexpr void SetIZone (double iZone)
 Sets the IZone range.
 
constexpr double GetP () const
 Gets the proportional coefficient.
 
constexpr double GetI () const
 Gets the integral coefficient.
 
constexpr double GetD () const
 Gets the differential coefficient.
 
constexpr double GetIZone () const
 Get the IZone range.
 
constexpr units::second_t GetPeriod () const
 Gets the period of this controller.
 
constexpr double GetErrorTolerance () const
 Gets the error tolerance of this controller.
 
constexpr double GetErrorDerivativeTolerance () const
 Gets the error derivative tolerance of this controller.
 
constexpr double GetPositionTolerance () const
 Gets the position tolerance of this controller.
 
constexpr double GetVelocityTolerance () const
 Gets the velocity tolerance of this controller.
 
constexpr double GetAccumulatedError () const
 Gets the accumulated error used in the integral calculation of this controller.
 
constexpr void SetSetpoint (double setpoint)
 Sets the setpoint for the PIDController.
 
constexpr double GetSetpoint () const
 Returns the current setpoint of the PIDController.
 
constexpr bool AtSetpoint () const
 Returns true if the error is within the tolerance of the setpoint.
 
constexpr void EnableContinuousInput (double minimumInput, double maximumInput)
 Enables continuous input.
 
constexpr void DisableContinuousInput ()
 Disables continuous input.
 
constexpr bool IsContinuousInputEnabled () const
 Returns true if continuous input is enabled.
 
constexpr void SetIntegratorRange (double minimumIntegral, double maximumIntegral)
 Sets the minimum and maximum contributions of the integral term.
 
constexpr void SetTolerance (double errorTolerance, double errorDerivativeTolerance=std::numeric_limits< double >::infinity())
 Sets the error which is considered tolerable for use with AtSetpoint().
 
constexpr double GetError () const
 Returns the difference between the setpoint and the measurement.
 
constexpr double GetErrorDerivative () const
 Returns the error derivative.
 
constexpr double GetPositionError () const
 Returns the difference between the setpoint and the measurement.
 
constexpr double GetVelocityError () const
 Returns the velocity error.
 
constexpr double Calculate (double measurement)
 Returns the next output of the PID controller.
 
constexpr double Calculate (double measurement, double setpoint)
 Returns the next output of the PID controller.
 
constexpr void Reset ()
 Reset the previous error, the integral term, and disable the controller.
 
void InitSendable (wpi::SendableBuilder &builder) override
 Initializes this Sendable object.
 
- Public Member Functions inherited from wpi::Sendable
virtual constexpr ~Sendable ()=default
 
- Public Member Functions inherited from wpi::SendableHelper< PIDController >
constexpr SendableHelper (const SendableHelper &rhs)=default
 
constexpr SendableHelper (SendableHelper &&rhs)
 
constexpr SendableHelperoperator= (const SendableHelper &rhs)=default
 
constexpr SendableHelperoperator= (SendableHelper &&rhs)
 

Additional Inherited Members

- Protected Member Functions inherited from wpi::SendableHelper< PIDController >
constexpr SendableHelper ()=default
 
constexpr ~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 )
inlineconstexpr

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

Parameters
KpThe proportional coefficient. Must be >= 0.
KiThe integral coefficient. Must be >= 0.
KdThe derivative coefficient. Must be >= 0.
periodThe period between controller updates in seconds. The default is 20 milliseconds. Must be positive.

◆ ~PIDController()

frc::PIDController::~PIDController ( )
constexproverridedefault

◆ PIDController() [2/3]

frc::PIDController::PIDController ( const PIDController & )
constexprdefault

◆ PIDController() [3/3]

frc::PIDController::PIDController ( PIDController && )
constexprdefault

Member Function Documentation

◆ AtSetpoint()

bool frc::PIDController::AtSetpoint ( ) const
inlineconstexpr

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

The error tolerance defauls to 0.05, and the error derivative tolerance defaults to ∞.

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

◆ Calculate() [1/2]

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

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 )
inlineconstexpr

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 ( )
inlineconstexpr

Disables continuous input.

◆ EnableContinuousInput()

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

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.

◆ GetAccumulatedError()

double frc::PIDController::GetAccumulatedError ( ) const
inlineconstexpr

Gets the accumulated error used in the integral calculation of this controller.

Returns
The accumulated error of this controller.

◆ GetD()

double frc::PIDController::GetD ( ) const
inlineconstexpr

Gets the differential coefficient.

Returns
differential coefficient

◆ GetError()

double frc::PIDController::GetError ( ) const
inlineconstexpr

Returns the difference between the setpoint and the measurement.

◆ GetErrorDerivative()

double frc::PIDController::GetErrorDerivative ( ) const
inlineconstexpr

Returns the error derivative.

◆ GetErrorDerivativeTolerance()

double frc::PIDController::GetErrorDerivativeTolerance ( ) const
inlineconstexpr

Gets the error derivative tolerance of this controller.

Defaults to ∞.

Returns
The error derivative tolerance of the controller.

◆ GetErrorTolerance()

double frc::PIDController::GetErrorTolerance ( ) const
inlineconstexpr

Gets the error tolerance of this controller.

Defaults to 0.05.

Returns
The error tolerance of the controller.

◆ GetI()

double frc::PIDController::GetI ( ) const
inlineconstexpr

Gets the integral coefficient.

Returns
integral coefficient

◆ GetIZone()

double frc::PIDController::GetIZone ( ) const
inlineconstexpr

Get the IZone range.

Returns
Maximum magnitude of error to allow integral control.

◆ GetP()

double frc::PIDController::GetP ( ) const
inlineconstexpr

Gets the proportional coefficient.

Returns
proportional coefficient

◆ GetPeriod()

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

Gets the period of this controller.

Returns
The period of the controller.

◆ GetPositionError()

double frc::PIDController::GetPositionError ( ) const
inlineconstexpr

Returns the difference between the setpoint and the measurement.

Deprecated
Use GetError() instead.

◆ GetPositionTolerance()

double frc::PIDController::GetPositionTolerance ( ) const
inlineconstexpr

Gets the position tolerance of this controller.

Returns
The position tolerance of the controller.
Deprecated
Use GetErrorTolerance() instead.

◆ GetSetpoint()

double frc::PIDController::GetSetpoint ( ) const
inlineconstexpr

Returns the current setpoint of the PIDController.

Returns
The current setpoint.

◆ GetVelocityError()

double frc::PIDController::GetVelocityError ( ) const
inlineconstexpr

Returns the velocity error.

Deprecated
Use GetErrorDerivative() instead.

◆ GetVelocityTolerance()

double frc::PIDController::GetVelocityTolerance ( ) const
inlineconstexpr

Gets the velocity tolerance of this controller.

Returns
The velocity tolerance of the controller.
Deprecated
Use GetErrorDerivativeTolerance() instead.

◆ 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
inlineconstexpr

Returns true if continuous input is enabled.

◆ operator=() [1/2]

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

◆ operator=() [2/2]

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

◆ Reset()

void frc::PIDController::Reset ( )
inlineconstexpr

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

◆ SetD()

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

Sets the differential coefficient of the PID controller gain.

Parameters
KdThe differential coefficient. Must be >= 0.

◆ SetI()

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

Sets the integral coefficient of the PID controller gain.

Parameters
KiThe integral coefficient. Must be >= 0.

◆ SetIntegratorRange()

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

Sets the minimum and maximum contributions of the integral term.

The internal integrator is clamped so that the integral term's contribution to the output stays between minimumIntegral and maximumIntegral. This prevents integral windup.

Parameters
minimumIntegralThe minimum contribution of the integral term.
maximumIntegralThe maximum contribution of the integral term.

◆ SetIZone()

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

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. Must be >= 0.

◆ SetP()

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

Sets the proportional coefficient of the PID controller gain.

Parameters
KpThe proportional coefficient. Must be >= 0.

◆ SetPID()

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

Sets the PID Controller gain parameters.

Sets the proportional, integral, and differential coefficients.

Parameters
KpThe proportional coefficient. Must be >= 0.
KiThe integral coefficient. Must be >= 0.
KdThe differential coefficient. Must be >= 0.

◆ SetSetpoint()

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

Sets the setpoint for the PIDController.

Parameters
setpointThe desired setpoint.

◆ SetTolerance()

void frc::PIDController::SetTolerance ( double errorTolerance,
double errorDerivativeTolerance = std::numeric_limits<double>::infinity() )
inlineconstexpr

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

Parameters
errorToleranceerror which is tolerable.
errorDerivativeToleranceerror derivative which is tolerable.

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