35 units::second_t period = 20_ms);
53 void SetPID(
double Kp,
double Ki,
double Kd);
198 double positionTolerance,
199 double velocityTolerance = std::numeric_limits<double>::infinity());
244 double m_iZone = std::numeric_limits<double>::infinity();
247 units::second_t m_period;
249 double m_maximumIntegral = 1.0;
251 double m_minimumIntegral = -1.0;
253 double m_maximumInput = 0;
255 double m_minimumInput = 0;
258 bool m_continuous =
false;
261 double m_positionError = 0;
262 double m_velocityError = 0;
266 double m_prevError = 0;
269 double m_totalError = 0;
272 double m_positionTolerance = 0.05;
273 double m_velocityTolerance = std::numeric_limits<double>::infinity();
275 double m_setpoint = 0;
276 double m_measurement = 0;
278 bool m_haveSetpoint =
false;
279 bool m_haveMeasurement =
false;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Implements a PID control loop.
Definition: PIDController.h:23
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
double Calculate(double measurement)
Returns the next output of the PID controller.
double GetIZone() const
Get the IZone range.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
double GetP() const
Gets the proportional coefficient.
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
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.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
double GetPositionTolerance() const
Gets the position tolerance of this controller.
double GetI() const
Gets the integral coefficient.
void DisableContinuousInput()
Disables continuous input.
double GetD() const
Gets the differential coefficient.
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
PIDController(const PIDController &)=default
void SetIZone(double iZone)
Sets the IZone range.
void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void Reset()
Reset the previous error, the integral term, and disable the controller.
double GetVelocityError() const
Returns the velocity error.
units::second_t GetPeriod() const
Gets the period of this controller.
PIDController & operator=(const PIDController &)=default
double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
~PIDController() override=default
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
PIDController(PIDController &&)=default
PIDController & operator=(PIDController &&)=default
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition: SendableBuilder.h:18
A helper class for use with objects that add themselves to SendableRegistry.
Definition: SendableHelper.h:19
Interface for Sendable objects.
Definition: Sendable.h:16
Definition: ProfiledPIDCommand.h:18
Definition: AprilTagPoseEstimator.h:15