mirror of https://github.com/ArduPilot/ardupilot
AP fix attitude hil.
we where waiting on new_data that had no way of getting there.
This commit is contained in:
parent
9d67f67741
commit
188cc69008
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue