WPILibC++ 2024.3.2
frc::ProfiledPIDController< Distance > Class Template Reference

Implements a PID control loop whose setpoint is constrained by a trapezoid profile. More...

#include <frc/controller/ProfiledPIDController.h>

Inheritance diagram for frc::ProfiledPIDController< Distance >:
wpi::Sendable wpi::SendableHelper< ProfiledPIDController< Distance > >

Public Types

using Distance_t = units::unit_t< Distance >
 
using Velocity = units::compound_unit< Distance, units::inverse< units::seconds > >
 
using Velocity_t = units::unit_t< Velocity >
 
using Acceleration = units::compound_unit< Velocity, units::inverse< units::seconds > >
 
using Acceleration_t = units::unit_t< Acceleration >
 
using State = typename TrapezoidProfile< Distance >::State
 
using Constraints = typename TrapezoidProfile< Distance >::Constraints
 

Public Member Functions

 ProfiledPIDController (double Kp, double Ki, double Kd, Constraints constraints, units::second_t period=20_ms)
 Allocates a ProfiledPIDController with the given constants for Kp, Ki, and Kd. More...
 
 ~ProfiledPIDController () override=default
 
 ProfiledPIDController (const ProfiledPIDController &)=default
 
ProfiledPIDControlleroperator= (const ProfiledPIDController &)=default
 
 ProfiledPIDController (ProfiledPIDController &&)=default
 
ProfiledPIDControlleroperator= (ProfiledPIDController &&)=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 SetGoal (State goal)
 Sets the goal for the ProfiledPIDController. More...
 
void SetGoal (Distance_t goal)
 Sets the goal for the ProfiledPIDController. More...
 
State GetGoal () const
 Gets the goal for the ProfiledPIDController. More...
 
bool AtGoal () const
 Returns true if the error is within the tolerance of the error. More...
 
void SetConstraints (Constraints constraints)
 Set velocity and acceleration constraints for goal. More...
 
Constraints GetConstraints ()
 Get the velocity and acceleration constraints for this controller. More...
 
State GetSetpoint () const
 Returns the current setpoint of the ProfiledPIDController. More...
 
bool AtSetpoint () const
 Returns true if the error is within the tolerance of the error. More...
 
void EnableContinuousInput (Distance_t minimumInput, Distance_t maximumInput)
 Enables continuous input. More...
 
void DisableContinuousInput ()
 Disables continuous input. More...
 
void SetIntegratorRange (double minimumIntegral, double maximumIntegral)
 Sets the minimum and maximum values for the integrator. More...
 
void SetTolerance (Distance_t positionTolerance, Velocity_t velocityTolerance=Velocity_t{ std::numeric_limits< double >::infinity()})
 Sets the error which is considered tolerable for use with AtSetpoint(). More...
 
Distance_t GetPositionError () const
 Returns the difference between the setpoint and the measurement. More...
 
Velocity_t GetVelocityError () const
 Returns the change in error per second. More...
 
double Calculate (Distance_t measurement)
 Returns the next output of the PID controller. More...
 
double Calculate (Distance_t measurement, State goal)
 Returns the next output of the PID controller. More...
 
double Calculate (Distance_t measurement, Distance_t goal)
 Returns the next output of the PID controller. More...
 
double Calculate (Distance_t measurement, Distance_t goal, typename frc::TrapezoidProfile< Distance >::Constraints constraints)
 Returns the next output of the PID controller. More...
 
void Reset (const State &measurement)
 Reset the previous error and the integral term. More...
 
void Reset (Distance_t measuredPosition, Velocity_t measuredVelocity)
 Reset the previous error and the integral term. More...
 
void Reset (Distance_t measuredPosition)
 Reset the previous error and the integral term. 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< ProfiledPIDController< Distance > >
 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< ProfiledPIDController< Distance > >
 SendableHelper ()=default
 
 ~SendableHelper ()
 

Detailed Description

template<class Distance>
class frc::ProfiledPIDController< Distance >

Implements a PID control loop whose setpoint is constrained by a trapezoid profile.

Member Typedef Documentation

◆ Acceleration

template<class Distance >
using frc::ProfiledPIDController< Distance >::Acceleration = units::compound_unit<Velocity, units::inverse<units::seconds> >

◆ Acceleration_t

template<class Distance >
using frc::ProfiledPIDController< Distance >::Acceleration_t = units::unit_t<Acceleration>

◆ Constraints

template<class Distance >
using frc::ProfiledPIDController< Distance >::Constraints = typename TrapezoidProfile<Distance>::Constraints

◆ Distance_t

template<class Distance >
using frc::ProfiledPIDController< Distance >::Distance_t = units::unit_t<Distance>

◆ State

template<class Distance >
using frc::ProfiledPIDController< Distance >::State = typename TrapezoidProfile<Distance>::State

◆ Velocity

template<class Distance >
using frc::ProfiledPIDController< Distance >::Velocity = units::compound_unit<Distance, units::inverse<units::seconds> >

◆ Velocity_t

template<class Distance >
using frc::ProfiledPIDController< Distance >::Velocity_t = units::unit_t<Velocity>

Constructor & Destructor Documentation

◆ ProfiledPIDController() [1/3]

template<class Distance >
frc::ProfiledPIDController< Distance >::ProfiledPIDController ( double  Kp,
double  Ki,
double  Kd,
Constraints  constraints,
units::second_t  period = 20_ms 
)
inline

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

Users should call reset() when they first start running the controller to avoid unwanted behavior.

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

◆ ~ProfiledPIDController()

template<class Distance >
frc::ProfiledPIDController< Distance >::~ProfiledPIDController ( )
overridedefault

◆ ProfiledPIDController() [2/3]

template<class Distance >
frc::ProfiledPIDController< Distance >::ProfiledPIDController ( const ProfiledPIDController< Distance > &  )
default

◆ ProfiledPIDController() [3/3]

template<class Distance >
frc::ProfiledPIDController< Distance >::ProfiledPIDController ( ProfiledPIDController< Distance > &&  )
default

Member Function Documentation

◆ AtGoal()

template<class Distance >
bool frc::ProfiledPIDController< Distance >::AtGoal ( ) const
inline

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

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

◆ AtSetpoint()

template<class Distance >
bool frc::ProfiledPIDController< Distance >::AtSetpoint ( ) const
inline

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

Currently this just reports on target as the actual value passes through the setpoint. Ideally it should be based on being within the tolerance for some period of time.

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

◆ Calculate() [1/4]

template<class Distance >
double frc::ProfiledPIDController< Distance >::Calculate ( Distance_t  measurement)
inline

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.

◆ Calculate() [2/4]

template<class Distance >
double frc::ProfiledPIDController< Distance >::Calculate ( Distance_t  measurement,
Distance_t  goal 
)
inline

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
goalThe new goal of the controller.

◆ Calculate() [3/4]

template<class Distance >
double frc::ProfiledPIDController< Distance >::Calculate ( Distance_t  measurement,
Distance_t  goal,
typename frc::TrapezoidProfile< Distance >::Constraints  constraints 
)
inline

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
goalThe new goal of the controller.
constraintsVelocity and acceleration constraints for goal.

◆ Calculate() [4/4]

template<class Distance >
double frc::ProfiledPIDController< Distance >::Calculate ( Distance_t  measurement,
State  goal 
)
inline

Returns the next output of the PID controller.

Parameters
measurementThe current measurement of the process variable.
goalThe new goal of the controller.

◆ DisableContinuousInput()

template<class Distance >
void frc::ProfiledPIDController< Distance >::DisableContinuousInput ( )
inline

Disables continuous input.

◆ EnableContinuousInput()

template<class Distance >
void frc::ProfiledPIDController< Distance >::EnableContinuousInput ( Distance_t  minimumInput,
Distance_t  maximumInput 
)
inline

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.

◆ GetConstraints()

template<class Distance >
Constraints frc::ProfiledPIDController< Distance >::GetConstraints ( )
inline

Get the velocity and acceleration constraints for this controller.

Returns
Velocity and acceleration constraints.

◆ GetD()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetD ( ) const
inline

Gets the differential coefficient.

Returns
differential coefficient

◆ GetGoal()

template<class Distance >
State frc::ProfiledPIDController< Distance >::GetGoal ( ) const
inline

Gets the goal for the ProfiledPIDController.

◆ GetI()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetI ( ) const
inline

Gets the integral coefficient.

Returns
integral coefficient

◆ GetIZone()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetIZone ( ) const
inline

Get the IZone range.

Returns
Maximum magnitude of error to allow integral control.

◆ GetP()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetP ( ) const
inline

Gets the proportional coefficient.

Returns
proportional coefficient

◆ GetPeriod()

template<class Distance >
units::second_t frc::ProfiledPIDController< Distance >::GetPeriod ( ) const
inline

Gets the period of this controller.

Returns
The period of the controller.

◆ GetPositionError()

template<class Distance >
Distance_t frc::ProfiledPIDController< Distance >::GetPositionError ( ) const
inline

Returns the difference between the setpoint and the measurement.

Returns
The error.

◆ GetPositionTolerance()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetPositionTolerance ( ) const
inline

Gets the position tolerance of this controller.

Returns
The position tolerance of the controller.

◆ GetSetpoint()

template<class Distance >
State frc::ProfiledPIDController< Distance >::GetSetpoint ( ) const
inline

Returns the current setpoint of the ProfiledPIDController.

Returns
The current setpoint.

◆ GetVelocityError()

template<class Distance >
Velocity_t frc::ProfiledPIDController< Distance >::GetVelocityError ( ) const
inline

Returns the change in error per second.

◆ GetVelocityTolerance()

template<class Distance >
double frc::ProfiledPIDController< Distance >::GetVelocityTolerance ( ) const
inline

Gets the velocity tolerance of this controller.

Returns
The velocity tolerance of the controller.

◆ InitSendable()

template<class Distance >
void frc::ProfiledPIDController< Distance >::InitSendable ( wpi::SendableBuilder builder)
inlineoverridevirtual

Initializes this Sendable object.

Parameters
buildersendable builder

Implements wpi::Sendable.

◆ operator=() [1/2]

template<class Distance >
ProfiledPIDController & frc::ProfiledPIDController< Distance >::operator= ( const ProfiledPIDController< Distance > &  )
default

◆ operator=() [2/2]

template<class Distance >
ProfiledPIDController & frc::ProfiledPIDController< Distance >::operator= ( ProfiledPIDController< Distance > &&  )
default

◆ Reset() [1/3]

template<class Distance >
void frc::ProfiledPIDController< Distance >::Reset ( const State measurement)
inline

Reset the previous error and the integral term.

Parameters
measurementThe current measured State of the system.

◆ Reset() [2/3]

template<class Distance >
void frc::ProfiledPIDController< Distance >::Reset ( Distance_t  measuredPosition)
inline

Reset the previous error and the integral term.

Parameters
measuredPositionThe current measured position of the system. The velocity is assumed to be zero.

◆ Reset() [3/3]

template<class Distance >
void frc::ProfiledPIDController< Distance >::Reset ( Distance_t  measuredPosition,
Velocity_t  measuredVelocity 
)
inline

Reset the previous error and the integral term.

Parameters
measuredPositionThe current measured position of the system.
measuredVelocityThe current measured velocity of the system.

◆ SetConstraints()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetConstraints ( Constraints  constraints)
inline

Set velocity and acceleration constraints for goal.

Parameters
constraintsVelocity and acceleration constraints for goal.

◆ SetD()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetD ( double  Kd)
inline

Sets the differential coefficient of the PID controller gain.

Parameters
KdThe differential coefficient. Must be >= 0.

◆ SetGoal() [1/2]

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetGoal ( Distance_t  goal)
inline

Sets the goal for the ProfiledPIDController.

Parameters
goalThe desired unprofiled setpoint.

◆ SetGoal() [2/2]

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetGoal ( State  goal)
inline

Sets the goal for the ProfiledPIDController.

Parameters
goalThe desired unprofiled setpoint.

◆ SetI()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetI ( double  Ki)
inline

Sets the integral coefficient of the PID controller gain.

Parameters
KiThe integral coefficient. Must be >= 0.

◆ SetIntegratorRange()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetIntegratorRange ( double  minimumIntegral,
double  maximumIntegral 
)
inline

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

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetIZone ( double  iZone)
inline

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

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetP ( double  Kp)
inline

Sets the proportional coefficient of the PID controller gain.

Parameters
KpThe proportional coefficient. Must be >= 0.

◆ SetPID()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetPID ( double  Kp,
double  Ki,
double  Kd 
)
inline

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.

◆ SetTolerance()

template<class Distance >
void frc::ProfiledPIDController< Distance >::SetTolerance ( Distance_t  positionTolerance,
Velocity_t  velocityTolerance = Velocity_t{ std::numeric_limits<double>::infinity()} 
)
inline

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: