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

View File

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