AP_LeadFilter: bug fix so velocity * _lag is used (otherwise we are assuming a 1sec lag)

This commit is contained in:
rmackay9 2012-09-20 13:17:42 +09:00
parent 2c36693a50
commit 2110231ee3
1 changed files with 1 additions and 1 deletions

View File

@ -40,5 +40,5 @@ AP_LeadFilter::get_position(int32_t pos, int16_t vel)
// store velocity for next iteration
_last_velocity = vel;
return pos + vel + accel_contribution;
return pos + vel_contribution + accel_contribution;
}