AP_Compass: allow multiple COMPASS_LEARN runs per boot

This commit is contained in:
Andrew Tridgell 2018-10-20 10:43:49 +11:00
parent 026089747d
commit 23ddd994ec
1 changed files with 10 additions and 1 deletions

View File

@ -141,7 +141,16 @@ void CompassLearn::update(void)
} }
} }
compass.set_learn_type(Compass::LEARN_NONE, true); compass.set_learn_type(Compass::LEARN_NONE, true);
converged = true; // setup so use can trigger it again
converged = false;
sample_available = false;
num_samples = 0;
have_earth_field = false;
memset(predicted_offsets, 0, sizeof(predicted_offsets));
worst_error = 0;
best_error = 0;
best_yaw_deg = 0;
best_offsets.zero();
gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: finished"); gcs().send_text(MAV_SEVERITY_INFO, "CompassLearn: finished");
} }
} }