15#include "wpi/units/time.hpp"
40 wpi::units::second_t period = 20_ms)
41 : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) {
42 bool invalidGains =
false;
45 "Kp must be a non-negative number, got {}!", Kp);
50 "Ki must be a non-negative number, got {}!", Ki);
55 "Kd must be a non-negative number, got {}!", Kd);
67 "Controller period must be a positive number, got {}!",
71 "Controller period defaulted to 20ms.");
73 if (!std::is_constant_evaluated()) {
77 std::to_string(instances));
98 constexpr void SetPID(
double Kp,
double Ki,
double Kd) {
109 constexpr void SetP(
double Kp) { m_Kp = Kp; }
116 constexpr void SetI(
double Ki) { m_Ki = Ki; }
123 constexpr void SetD(
double Kd) { m_Kd = Kd; }
137 if (std::is_constant_evaluated() && iZone < 0) {
139 "IZone must be a non-negative number, got {}!", iZone);
149 constexpr double GetP()
const {
return m_Kp; }
156 constexpr double GetI()
const {
return m_Ki; }
163 constexpr double GetD()
const {
return m_Kd; }
170 constexpr double GetIZone()
const {
return m_iZone; }
177 constexpr wpi::units::second_t
GetPeriod()
const {
return m_period; }
192 return m_errorDerivativeTolerance;
209 m_setpoint = setpoint;
210 m_haveSetpoint =
true;
213 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
215 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
217 m_error = m_setpoint - m_measurement;
220 m_errorDerivative = (m_error - m_prevError) / m_period.value();
238 return m_haveMeasurement && m_haveSetpoint &&
240 gcem::abs(m_errorDerivative) < m_errorDerivativeTolerance;
254 double maximumInput) {
256 m_minimumInput = minimumInput;
257 m_maximumInput = maximumInput;
281 double maximumIntegral) {
282 m_minimumIntegral = minimumIntegral;
283 m_maximumIntegral = maximumIntegral;
293 double errorDerivativeTolerance =
294 std::numeric_limits<double>::infinity()) {
295 m_errorTolerance = errorTolerance;
296 m_errorDerivativeTolerance = errorDerivativeTolerance;
302 constexpr double GetError()
const {
return m_error; }
315 m_measurement = measurement;
316 m_prevError = m_error;
317 m_haveMeasurement =
true;
320 double errorBound = (m_maximumInput - m_minimumInput) / 2.0;
322 InputModulus(m_setpoint - m_measurement, -errorBound, errorBound);
324 m_error = m_setpoint - m_measurement;
327 m_errorDerivative = (m_error - m_prevError) / m_period.value();
333 }
else if (m_Ki != 0) {
335 std::clamp(m_totalError + m_error * m_period.value(),
336 m_minimumIntegral / m_Ki, m_maximumIntegral / m_Ki);
339 return m_Kp * m_error + m_Ki * m_totalError + m_Kd * m_errorDerivative;
348 constexpr double Calculate(
double measurement,
double setpoint) {
349 m_setpoint = setpoint;
350 m_haveSetpoint =
true;
361 m_errorDerivative = 0;
362 m_haveMeasurement =
false;
378 double m_iZone = std::numeric_limits<double>::infinity();
381 wpi::units::second_t m_period;
383 double m_maximumIntegral = 1.0;
385 double m_minimumIntegral = -1.0;
387 double m_maximumInput = 0;
389 double m_minimumInput = 0;
392 bool m_continuous =
false;
396 double m_errorDerivative = 0;
400 double m_prevError = 0;
403 double m_totalError = 0;
406 double m_errorTolerance = 0.05;
407 double m_errorDerivativeTolerance = std::numeric_limits<double>::infinity();
409 double m_setpoint = 0;
410 double m_measurement = 0;
412 bool m_haveSetpoint =
false;
413 bool m_haveMeasurement =
false;
416 inline static int instances = 0;
#define WPILIB_DLLEXPORT
Definition SymbolExports.hpp:36
static void ReportUsage(std::string_view resource, std::string_view data)
Definition MathShared.hpp:61
static void ReportError(const S &format, Args &&... args)
Definition MathShared.hpp:48
static void ReportWarning(const S &format, Args &&... args)
Definition MathShared.hpp:57
constexpr double GetIZone() const
Get the IZone range.
Definition PIDController.hpp:170
constexpr ~PIDController() override=default
constexpr wpi::units::second_t GetPeriod() const
Gets the period of this controller.
Definition PIDController.hpp:177
constexpr void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
Definition PIDController.hpp:109
constexpr double GetErrorTolerance() const
Gets the error tolerance of this controller.
Definition PIDController.hpp:184
constexpr void SetIZone(double iZone)
Sets the IZone range.
Definition PIDController.hpp:136
constexpr double Calculate(double measurement)
Returns the next output of the PID controller.
Definition PIDController.hpp:314
constexpr double GetSetpoint() const
Returns the current setpoint of the PIDController.
Definition PIDController.hpp:228
constexpr PIDController(PIDController &&)=default
constexpr bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
Definition PIDController.hpp:268
constexpr double GetD() const
Gets the differential coefficient.
Definition PIDController.hpp:163
constexpr PIDController & operator=(PIDController &&)=default
constexpr double Calculate(double measurement, double setpoint)
Returns the next output of the PID controller.
Definition PIDController.hpp:348
constexpr void Reset()
Reset the previous error, the integral term, and disable the controller.
Definition PIDController.hpp:357
constexpr void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
Definition PIDController.hpp:116
constexpr double GetError() const
Returns the difference between the setpoint and the measurement.
Definition PIDController.hpp:302
constexpr double GetAccumulatedError() const
Gets the accumulated error used in the integral calculation of this controller.
Definition PIDController.hpp:201
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.hpp:292
constexpr double GetErrorDerivativeTolerance() const
Gets the error derivative tolerance of this controller.
Definition PIDController.hpp:191
constexpr double GetP() const
Gets the proportional coefficient.
Definition PIDController.hpp:149
constexpr PIDController & operator=(const PIDController &)=default
constexpr void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition PIDController.hpp:98
constexpr double GetErrorDerivative() const
Returns the error derivative.
Definition PIDController.hpp:307
constexpr PIDController(double Kp, double Ki, double Kd, wpi::units::second_t period=20_ms)
Allocates a PIDController with the given constants for Kp, Ki, and Kd.
Definition PIDController.hpp:39
constexpr void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
Definition PIDController.hpp:253
constexpr double GetI() const
Gets the integral coefficient.
Definition PIDController.hpp:156
constexpr void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
Definition PIDController.hpp:123
constexpr void DisableContinuousInput()
Disables continuous input.
Definition PIDController.hpp:263
constexpr void SetSetpoint(double setpoint)
Sets the setpoint for the PIDController.
Definition PIDController.hpp:208
void InitSendable(wpi::util::SendableBuilder &builder) override
Initializes this Sendable object.
constexpr PIDController(const PIDController &)=default
constexpr void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum contributions of the integral term.
Definition PIDController.hpp:280
constexpr bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
Definition PIDController.hpp:237
Helper class for building Sendable dashboard representations.
Definition SendableBuilder.hpp:21
A helper class for use with objects that add themselves to SendableRegistry.
Definition SendableHelper.hpp:21
Interface for Sendable objects.
Definition Sendable.hpp:16
static void Add(Sendable *sendable, std::string_view name)
Adds an object to the registry.
constexpr T abs(const T x) noexcept
Compile-time absolute value function.
Definition abs.hpp:40
Definition LinearSystem.hpp:20
constexpr T InputModulus(T input, T minimumInput, T maximumInput)
Returns modulus of input.
Definition MathUtil.hpp:205