APM: reload airspeed and throttle after landing

this allows for restarting a mission after landing with reasonable
airspeed values
This commit is contained in:
Andrew Tridgell 2012-08-15 12:34:51 +10:00
parent f4023d1b44
commit b8521ff9ae
1 changed files with 6 additions and 0 deletions

View File

@ -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) {