35 units::second_t period = 20_ms);
53 void SetPID(
double Kp,
double Ki,
double Kd);
199 double positionTolerance,
200 double velocityTolerance = std::numeric_limits<double>::infinity());
245 double m_iZone = std::numeric_limits<double>::infinity();
248 units::second_t m_period;
250 double m_maximumIntegral = 1.0;
252 double m_minimumIntegral = -1.0;
254 double m_maximumInput = 0;
256 double m_minimumInput = 0;
259 bool m_continuous =
false;
262 double m_positionError = 0;
263 double m_velocityError = 0;
267 double m_prevError = 0;
270 double m_totalError = 0;
273 double m_positionTolerance = 0.05;
274 double m_velocityTolerance = std::numeric_limits<double>::infinity();
276 double m_setpoint = 0;
277 double m_measurement = 0;
279 bool m_haveSetpoint =
false;
280 bool m_haveMeasurement =
false;
#define WPILIB_DLLEXPORT
Definition: SymbolExports.h:36
Implements a PID control loop.
Definition: PIDController.h:23
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
PIDController & operator=(const PIDController &)=default
PIDController(const PIDController &)=default
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
units::second_t GetPeriod() const
Gets the period of this controller.
double GetIZone() const
Get the IZone range.
double GetP() const
Gets the proportional coefficient.
PIDController & operator=(PIDController &&)=default
void DisableContinuousInput()
Disables continuous input.
double GetD() const
Gets the differential coefficient.
PIDController(PIDController &&)=default
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
void SetIZone(double iZone)
Sets the IZone range.
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.
void Reset()
Reset the previous error, the integral term, and disable the controller.
~PIDController() override=default
double GetPositionTolerance() const
Gets the position tolerance of this controller.
double GetI() const
Gets the integral coefficient.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
double GetVelocityError() const
Returns the velocity error.
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.
Helper class for building Sendable dashboard representations.
Definition: SendableBuilder.h:21
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: AprilTagPoseEstimator.h:15