fixed imax load/save in PID

This commit is contained in:
Andrew Tridgell 2012-02-13 14:22:39 +11:00
parent c497ad9b7e
commit e7e7450f90

View File

@ -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();
}