ardupilot/libraries/AC_PID/AP_PIDInfo.h
Andy Piper fc76312fc3 AC_PID: use AP_Filter for notch configuration
enable filters with AP_FILTER_ENABLED
dynamically allocate notches
remove load/save for notches, update docs
move feedfoward update to update_all()
restrict load_gains() and save_gains() to just what autotune needs
add D_FF logging
2023-11-21 13:26:23 +11:00

23 lines
488 B
C

#pragma once
// This structure provides information on the internal member data of
// a PID. It provides an abstract way to pass PID information around,
// useful for logging and sending mavlink messages.
// It is also used to pass PID information into controllers...
struct AP_PIDInfo {
float target;
float actual;
float error;
float P;
float I;
float D;
float FF;
float DFF;
float Dmod;
float slew_rate;
bool limit;
bool PD_limit;
};