Plane: fixed target speed reload on landing

thanks to Doug for this fix!
This commit is contained in:
Andrew Tridgell 2013-02-11 11:40:36 +11:00
parent 3b8b04920a
commit 9d3224ef34
1 changed files with 9 additions and 5 deletions

View File

@ -350,12 +350,16 @@ static bool verify_land()
gcs_send_text_fmt(PSTR("Land Complete - Hold course %ld"), hold_course);
}
if (g_gps->ground_speed*0.01 < 3.0) {
// reload any airspeed or groundspeed parameters that may have
// been set for landing
// been set for landing. We don't do this till ground
// speed drops below 3.0 m/s as otherwise we will change
// target speeds too early.
g.airspeed_cruise_cm.load();
g.min_gndspeed_cm.load();
g.throttle_cruise.load();
}
}
if (hold_course != -1) {
// recalc bearing error with hold_course;