16 PID(
const float & initial_p = 0.0
f,
17 const float & initial_i = 0.0
f,
18 const float & initial_d = 0.0
f,
19 const int16_t & initial_imax = 0)
65 const int16_t imaxval) {
82 void kP(
const float v) {
85 void kI(
const float v) {
88 void kD(
const float v) {
114 float _get_pid(
float error, uint16_t dt,
float scaler);
float _integrator
integrator value
static const uint8_t _fCut
const DataFlash_Class::PID_Info & get_pid_info(void) const
A system for managing and storing variables that are of general interest to the system.
float _get_pid(float error, uint16_t dt, float scaler)
Object managing one PID control.
void operator()(const float p, const float i, const float d, const int16_t imaxval)
Overload the function call operator to permit relatively easy initialisation.
void reset()
Reset the whole PID state.
float _last_error
last error for derivative
DataFlash_Class::PID_Info _pid_info
PID(const float &initial_p=0.0f, const float &initial_i=0.0f, const float &initial_d=0.0f, const int16_t &initial_imax=0)
float _last_derivative
last derivative for low-pass filter
Common definitions and utility routines for the ArduPilot libraries.
float get_pid(float error, float scaler=1.0)
#define error(fmt, args ...)
void imax(const int16_t v)
uint32_t _last_t
last time get_pid() was called in millis
static const struct AP_Param::GroupInfo var_info[]
float get_integrator() const
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)