mirror of https://github.com/ArduPilot/ardupilot
fixed imax load/save in PID
This commit is contained in:
parent
37cabb4cfa
commit
23ed5c2cee
|
@ -73,6 +73,7 @@ PID::load_gains()
|
|||
_kp.load();
|
||||
_ki.load();
|
||||
_kd.load();
|
||||
_imax.load();
|
||||
}
|
||||
|
||||
void
|
||||
|
@ -81,4 +82,5 @@ PID::save_gains()
|
|||
_kp.save();
|
||||
_ki.save();
|
||||
_kd.save();
|
||||
_imax.save();
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue