AC_PID: log desired rate for VFF as well as AFF

This commit is contained in:
Andrew Tridgell 2015-05-24 12:20:32 +10:00
parent b45ab52015
commit 6000bb0c32
1 changed files with 1 additions and 0 deletions

View File

@ -56,6 +56,7 @@ AC_HELI_PID::AC_HELI_PID(float initial_p, float initial_i, float initial_d, floa
float AC_HELI_PID::get_vff(float requested_rate)
{
_pid_info.FF = (float)requested_rate * _vff;
_pid_info.desired = requested_rate;
return _pid_info.FF;
}