mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-10 16:44:18 -03:00
ArduCopter - remove unnecessary block for next GPS value before saving home location
This commit is contained in:
parent
66b95c14c5
commit
e146f225b1
@ -1339,14 +1339,7 @@ static void update_GPS(void)
|
|||||||
ground_start_count = 5;
|
ground_start_count = 5;
|
||||||
|
|
||||||
}else{
|
}else{
|
||||||
// block until we get a good fix
|
// save home to eeprom (we must have a good fix to have reached this point)
|
||||||
// -----------------------------
|
|
||||||
while (!g_gps->new_data || !g_gps->fix) {
|
|
||||||
g_gps->update();
|
|
||||||
// we need GCS update while waiting for GPS, to ensure
|
|
||||||
// we react to HIL mavlink
|
|
||||||
gcs_update();
|
|
||||||
}
|
|
||||||
init_home();
|
init_home();
|
||||||
ground_start_count = 0;
|
ground_start_count = 0;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user