10#include <units/time.h>
42 void SetPID(
double Kp,
double Ki,
double Kd);
174 double positionTolerance,
175 double velocityTolerance = std::numeric_limits<double>::infinity());
194 double Calculate(
double measurement,
double setpoint, units::second_t currentTimestamp);
217 double m_iZone = std::numeric_limits<double>::infinity();
219 double m_maximumIntegral = 1.0;
221 double m_minimumIntegral = -1.0;
223 double m_maximumInput = 0;
225 double m_minimumInput = 0;
228 bool m_continuous =
false;
231 double m_positionError = 0;
232 double m_velocityError = 0;
236 double m_prevError = 0;
239 double m_totalError = 0;
242 double m_positionTolerance = 0.05;
243 double m_velocityTolerance = std::numeric_limits<double>::infinity();
245 double m_setpoint = 0;
246 double m_measurement = 0;
248 bool m_haveSetpoint =
false;
249 bool m_haveMeasurement =
false;
251 double m_lastAppliedOutput;
254 units::second_t m_lastTimestamp;
Phoenix-centric PID controller taken from WPI's frc#PIDController class.
Definition PhoenixPIDController.hpp:22
void DisableContinuousInput()
Disables continuous input.
void SetI(double Ki)
Sets the integral coefficient of the PID controller gain.
bool IsContinuousInputEnabled() const
Returns true if continuous input is enabled.
double GetLastAppliedOutput() const
Returns the last applied output from this PID controller.
double GetPositionError() const
Returns the difference between the setpoint and the measurement.
PhoenixPIDController(double Kp, double Ki, double Kd)
Allocates a PhoenixPIDController with the given constants for Kp, Ki, and Kd.
void SetP(double Kp)
Sets the proportional coefficient of the PID controller gain.
void Reset()
Reset the previous error, the integral term, and disable the controller.
void SetIntegratorRange(double minimumIntegral, double maximumIntegral)
Sets the minimum and maximum values for the integrator.
double GetVelocityError() const
Returns the velocity error.
double GetSetpoint() const
Returns the current setpoint of the PIDController.
bool AtSetpoint() const
Returns true if the error is within the tolerance of the setpoint.
double GetP() const
Gets the proportional coefficient.
void SetD(double Kd)
Sets the differential coefficient of the PID controller gain.
double GetVelocityTolerance() const
Gets the velocity tolerance of this controller.
double GetI() const
Gets the integral coefficient.
double Calculate(double measurement, double setpoint, units::second_t currentTimestamp)
Returns the next output of the PID controller.
double GetPositionTolerance() const
Gets the position tolerance of this controller.
void EnableContinuousInput(double minimumInput, double maximumInput)
Enables continuous input.
void SetTolerance(double positionTolerance, double velocityTolerance=std::numeric_limits< double >::infinity())
Sets the error which is considered tolerable for use with AtSetpoint().
double GetIZone() const
Get the IZone range.
double GetD() const
Gets the differential coefficient.
void SetIZone(double iZone)
Sets the IZone range.
void SetPID(double Kp, double Ki, double Kd)
Sets the PID Controller gain parameters.
Definition motor_constants.h:14