ArduCopter - remove unnecessary block for next GPS value before saving home location

This commit is contained in:
Randy Mackay 2012-02-19 15:38:40 +09:00
parent 470ced9aad
commit 7c4ef140b9

View File

@ -1339,14 +1339,7 @@ static void update_GPS(void)
ground_start_count = 5;
}else{
// block until we get a good fix
// -----------------------------
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();
}
// save home to eeprom (we must have a good fix to have reached this point)
init_home();
ground_start_count = 0;
}