mirror of https://github.com/ArduPilot/ardupilot
APM: reload airspeed and throttle after landing
this allows for restarting a mission after landing with reasonable airspeed values
This commit is contained in:
parent
f4023d1b44
commit
b8521ff9ae
|
@ -334,6 +334,12 @@ static bool verify_land()
|
|||
hold_course = ahrs.yaw_sensor;
|
||||
gcs_send_text_fmt(PSTR("Holding course %ld"), hold_course);
|
||||
}
|
||||
|
||||
// reload any airspeed or groundspeed parameters that may have
|
||||
// been set for landing
|
||||
g.airspeed_cruise_cm.load();
|
||||
g.min_gndspeed_cm.load();
|
||||
g.throttle_cruise.load();
|
||||
}
|
||||
|
||||
if (hold_course != -1) {
|
||||
|
|
Loading…
Reference in New Issue