WPILibC++ 2024.3.2
|
Implements a PID control loop whose setpoint is constrained by a trapezoid profile. More...
#include <frc/controller/ProfiledPIDController.h>
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 | |
ProfiledPIDController & | operator= (const ProfiledPIDController &)=default |
ProfiledPIDController (ProfiledPIDController &&)=default | |
ProfiledPIDController & | operator= (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) | |
SendableHelper & | operator= (const SendableHelper &rhs)=default |
SendableHelper & | operator= (SendableHelper &&rhs) |
Additional Inherited Members | |
Protected Member Functions inherited from wpi::SendableHelper< ProfiledPIDController< Distance > > | |
SendableHelper ()=default | |
~SendableHelper () | |
Implements a PID control loop whose setpoint is constrained by a trapezoid profile.
using frc::ProfiledPIDController< Distance >::Acceleration = units::compound_unit<Velocity, units::inverse<units::seconds> > |
using frc::ProfiledPIDController< Distance >::Acceleration_t = units::unit_t<Acceleration> |
using frc::ProfiledPIDController< Distance >::Constraints = typename TrapezoidProfile<Distance>::Constraints |
using frc::ProfiledPIDController< Distance >::Distance_t = units::unit_t<Distance> |
using frc::ProfiledPIDController< Distance >::State = typename TrapezoidProfile<Distance>::State |
using frc::ProfiledPIDController< Distance >::Velocity = units::compound_unit<Distance, units::inverse<units::seconds> > |
using frc::ProfiledPIDController< Distance >::Velocity_t = units::unit_t<Velocity> |
|
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.
Kp | The proportional coefficient. Must be >= 0. |
Ki | The integral coefficient. Must be >= 0. |
Kd | The derivative coefficient. Must be >= 0. |
constraints | Velocity and acceleration constraints for goal. |
period | The period between controller updates in seconds. The default is 20 milliseconds. Must be positive. |
|
overridedefault |
|
default |
|
default |
|
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.
|
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.
|
inline |
Returns the next output of the PID controller.
measurement | The current measurement of the process variable. |
|
inline |
Returns the next output of the PID controller.
measurement | The current measurement of the process variable. |
goal | The new goal of the controller. |
|
inline |
Returns the next output of the PID controller.
measurement | The current measurement of the process variable. |
goal | The new goal of the controller. |
constraints | Velocity and acceleration constraints for goal. |
|
inline |
Returns the next output of the PID controller.
measurement | The current measurement of the process variable. |
goal | The new goal of the controller. |
|
inline |
Disables continuous input.
|
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.
minimumInput | The minimum value expected from the input. |
maximumInput | The maximum value expected from the input. |
|
inline |
Get the velocity and acceleration constraints for this controller.
|
inline |
Gets the differential coefficient.
|
inline |
Gets the goal for the ProfiledPIDController.
|
inline |
Gets the integral coefficient.
|
inline |
Get the IZone range.
|
inline |
Gets the proportional coefficient.
|
inline |
Gets the period of this controller.
|
inline |
Returns the difference between the setpoint and the measurement.
|
inline |
Gets the position tolerance of this controller.
|
inline |
Returns the current setpoint of the ProfiledPIDController.
|
inline |
Returns the change in error per second.
|
inline |
Gets the velocity tolerance of this controller.
|
inlineoverridevirtual |
|
default |
|
default |
|
inline |
Reset the previous error and the integral term.
measurement | The current measured State of the system. |
|
inline |
Reset the previous error and the integral term.
measuredPosition | The current measured position of the system. The velocity is assumed to be zero. |
|
inline |
Reset the previous error and the integral term.
measuredPosition | The current measured position of the system. |
measuredVelocity | The current measured velocity of the system. |
|
inline |
Set velocity and acceleration constraints for goal.
constraints | Velocity and acceleration constraints for goal. |
|
inline |
Sets the differential coefficient of the PID controller gain.
Kd | The differential coefficient. Must be >= 0. |
|
inline |
Sets the goal for the ProfiledPIDController.
goal | The desired unprofiled setpoint. |
|
inline |
Sets the goal for the ProfiledPIDController.
goal | The desired unprofiled setpoint. |
|
inline |
Sets the integral coefficient of the PID controller gain.
Ki | The integral coefficient. Must be >= 0. |
|
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.
minimumIntegral | The minimum value of the integrator. |
maximumIntegral | The maximum value of the integrator. |
|
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.
iZone | Maximum magnitude of error to allow integral control. Must be >= 0. |
|
inline |
Sets the proportional coefficient of the PID controller gain.
Kp | The proportional coefficient. Must be >= 0. |
|
inline |
Sets the PID Controller gain parameters.
Sets the proportional, integral, and differential coefficients.
Kp | The proportional coefficient. Must be >= 0. |
Ki | The integral coefficient. Must be >= 0. |
Kd | The differential coefficient. Must be >= 0. |
|
inline |
Sets the error which is considered tolerable for use with AtSetpoint().
positionTolerance | Position error which is tolerable. |
velocityTolerance | Velocity error which is tolerable. |