41 units::second_t period = 20_ms)
42 : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) {
43 bool invalidGains =
false;
46 "Kp must be a non-negative number, got {}!", Kp);
51 "Ki must be a non-negative number, got {}!", Ki);
56 "Kd must be a non-negative number, got {}!", Kd);
68 "Controller period must be a positive number, got {}!",
72 "Controller period defaulted to 20ms.");
74 if (!std::is_constant_evaluated()) {
99 constexpr void SetPID(
double Kp,
double Ki,
double Kd) {
110 constexpr void SetP(
double Kp) { m_Kp = Kp; }
117 constexpr void SetI(
double Ki) { m_Ki = Ki; }
124 constexpr void SetD(
double Kd) { m_Kd = Kd; }
138 if (std::is_constant_evaluated() && iZone < 0) {
140 "IZone must be a non-negative number, got {}!", iZone);
150 constexpr double GetP()
const {
return m_Kp; }
157 constexpr double GetI()
const {
return m_Ki; }
164 constexpr double GetD()
const {
return m_Kd; }
171 constexpr double GetIZone()
const {
return m_iZone; }
178 constexpr units::second_t
GetPeriod()
const {
return m_period; }
193 return m_errorDerivativeTolerance;
202 [[deprecated(
"Use the GetErrorTolerance method instead.")]]
204 return m_errorTolerance;
213 [[deprecated(
"Use the GetErrorDerivativeTolerance method instead.")]]
215 return m_errorDerivativeTolerance;
232 m_setpoint = setpoint;
233 m_haveSetpoint =
true;
236 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
238 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
240 m_error = m_setpoint - m_measurement;
243 m_errorDerivative = (m_error - m_prevError) / m_period.value();
261 return m_haveMeasurement && m_haveSetpoint &&
263 gcem::abs(m_errorDerivative) < m_errorDerivativeTolerance;
277 double maximumInput) {
279 m_minimumInput = minimumInput;
280 m_maximumInput = maximumInput;
304 double maximumIntegral) {
305 m_minimumIntegral = minimumIntegral;
306 m_maximumIntegral = maximumIntegral;
316 double errorDerivativeTolerance =
317 std::numeric_limits<double>::infinity()) {
318 m_errorTolerance = errorTolerance;
319 m_errorDerivativeTolerance = errorDerivativeTolerance;
325 constexpr double GetError()
const {
return m_error; }
336 [[deprecated(
"Use GetError method instead.")]]
345 [[deprecated(
"Use GetErrorDerivative method instead.")]]
347 return m_errorDerivative;
356 m_measurement = measurement;
357 m_prevError = m_error;
358 m_haveMeasurement =
true;
361 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
363 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
365 m_error = m_setpoint - m_measurement;
368 m_errorDerivative = (m_error - m_prevError) / m_period.value();
374 }
else if (m_Ki != 0) {
376 std::clamp(m_totalError + m_error * m_period.value(),
377 m_minimumIntegral / m_Ki, m_maximumIntegral / m_Ki);
380 return m_Kp * m_error + m_Ki * m_totalError + m_Kd * m_errorDerivative;
389 constexpr double Calculate(
double measurement,
double setpoint) {
390 m_setpoint = setpoint;
391 m_haveSetpoint =
true;
392 return Calculate(measurement);
402 m_errorDerivative = 0;
403 m_haveMeasurement =
false;
419 double m_iZone = std::numeric_limits<double>::infinity();
422 units::second_t m_period;
424 double m_maximumIntegral = 1.0;
426 double m_minimumIntegral = -1.0;
428 double m_maximumInput = 0;
430 double m_minimumInput = 0;
433 bool m_continuous =
false;
437 double m_errorDerivative = 0;
441 double m_prevError = 0;
444 double m_totalError = 0;
447 double m_errorTolerance = 0.05;
448 double m_errorDerivativeTolerance = std::numeric_limits<double>::infinity();
450 double m_setpoint = 0;
451 double m_measurement = 0;
453 bool m_haveSetpoint =
false;
454 bool m_haveMeasurement =
false;
457 inline static int instances = 0;
#define WPILIB_DLLEXPORT
Definition SymbolExports.h:36
Implements a PID control loop.
Definition PIDController.h:29
constexpr bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition PIDController.h:291
constexpr units::second_t GetPeriod() const
Gets the period of this controller.
Definition PIDController.h:178
constexpr PIDController(PIDController &&)=default
constexpr double Calculate(double measurement)
Returns the next output of the PID controller.
Definition PIDController.h:355
constexpr double GetErrorDerivativeTolerance() const
Gets the error derivative tolerance of this controller.
Definition PIDController.h:192
constexpr double GetI() const
Gets the integral coefficient.
Definition PIDController.h:157
constexpr void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
Definition PIDController.h:276
constexpr double GetD() const
Gets the differential coefficient.
Definition PIDController.h:164
constexpr void DisableContinuousInput()
Disables continuous input.
Definition PIDController.h:286
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
Definition PIDController.h:260
constexpr void SetTolerance(double errorTolerance, double errorDerivativeTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
Definition PIDController.h:315
constexpr double GetVelocityError() const
Returns the velocity error.
Definition PIDController.h:346
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.
Definition PIDController.h:40
constexpr double GetPositionTolerance() const
Gets the position tolerance of this controller.
Definition PIDController.h:203
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition PIDController.h:124
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition PIDController.h:137
constexpr double GetErrorTolerance() const
Gets the error tolerance of this controller.
Definition PIDController.h:185
constexpr double GetP() const
Gets the proportional coefficient.
Definition PIDController.h:150
constexpr PIDController & operator=(PIDController &&)=default
constexpr PIDController(const PIDController &)=default
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition PIDController.h:303
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition PIDController.h:224
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition PIDController.h:99
constexpr double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
Definition PIDController.h:389
constexpr void Reset()
Reset the previous error, the integral term, and disable the controller.
Definition PIDController.h:398
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition PIDController.h:117
constexpr PIDController & operator=(const PIDController &)=default
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition PIDController.h:110
constexpr double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
Definition PIDController.h:214
void InitSendable(wpi::SendableBuilder &builder) override
Initializes this Sendable object.
constexpr double GetErrorDerivative() const
Returns the error derivative.
Definition PIDController.h:330
constexpr ~PIDController() override=default
constexpr void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
Definition PIDController.h:231
constexpr double GetError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.h:325
constexpr double GetIZone() const
Get the IZone range.
Definition PIDController.h:171
constexpr double GetSetpoint() const
Returns the current setpoint of the PIDController.
Definition PIDController.h:251
constexpr double GetPositionError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.h:337
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:21
Interface for Sendable objects.
Definition Sendable.h:16
static void Add(Sendable *sendable, std::string_view name)
Adds an object to the registry.
static void ReportError(const S &format, Args &&... args)
Definition MathShared.h:62
static void ReportUsage(MathUsageId id, int count)
Definition MathShared.h:75
static void ReportWarning(const S &format, Args &&... args)
Definition MathShared.h:71
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.h:95
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
@ kController_PIDController2