AP fix attitude hil.

we where waiting on new_data that had no way of getting there.
This commit is contained in:
Michael Oborne 2012-08-30 07:54:20 +08:00
parent 97aa98015d
commit 1e7adac365
1 changed files with 4 additions and 0 deletions

View File

@ -235,6 +235,10 @@ void init_home()
// -----------------------------
while (!g_gps->new_data || !g_gps->fix) {
g_gps->update();
#if HIL_MODE != HIL_MODE_DISABLED
// update hil gps so we have new_data
gcs_update();
#endif
}
home.id = MAV_CMD_NAV_WAYPOINT;