mirror of https://github.com/ArduPilot/ardupilot
Plane: fixed target speed reload on landing
thanks to Doug for this fix!
This commit is contained in:
parent
3b8b04920a
commit
9d3224ef34
|
@ -350,12 +350,16 @@ 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);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (g_gps->ground_speed*0.01 < 3.0) {
|
||||||
// reload any airspeed or groundspeed parameters that may have
|
// 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.airspeed_cruise_cm.load();
|
||||||
g.min_gndspeed_cm.load();
|
g.min_gndspeed_cm.load();
|
||||||
g.throttle_cruise.load();
|
g.throttle_cruise.load();
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (hold_course != -1) {
|
if (hold_course != -1) {
|
||||||
// recalc bearing error with hold_course;
|
// recalc bearing error with hold_course;
|
||||||
|
|
Loading…
Reference in New Issue