44 if (_last_t == 0 || dt > 1000) {
55 delta_time = (float)dt / 1000.0
f;
62 if ((fabsf(
_kd) > 0) && (dt > 0)) {
79 ((delta_time / (RC + delta_time)) *
97 if ((fabsf(
_ki) > 0) && (dt > 0)) {
Generic PID algorithm, with EEPROM-backed storage of constants.
#define AP_GROUPINFO(name, idx, clazz, element, def)
float _integrator
integrator value
static const uint8_t _fCut
Object managing one PID control.
void reset()
Reset the whole PID state.
float _last_error
last error for derivative
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
DataFlash_Class::PID_Info _pid_info
float _last_derivative
last derivative for low-pass filter
float get_pid(float error, float scaler=1.0)
#define error(fmt, args ...)
uint32_t _last_t
last time get_pid() was called in millis
DerivativeFilter< float, 11 > derivative
static const struct AP_Param::GroupInfo var_info[]