AP_Landing: implement continue after land for fixed wing landings

this makes touch and go missions possible
This commit is contained in:
Andrew Tridgell 2020-03-04 14:43:37 +11:00 committed by Randy Mackay
parent e673bd8909
commit d9d53d380d
1 changed files with 13 additions and 1 deletions

View File

@ -89,12 +89,13 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
const bool below_flare_sec = (flare_sec > 0 && height <= sink_rate * flare_sec);
const bool probably_crashed = (aparm.crash_detection_enable && fabsf(sink_rate) < 0.2f && !is_flying);
const AP_GPS &gps = AP::gps();
if ((on_approach_stage && below_flare_alt) ||
(on_approach_stage && below_flare_sec && (wp_proportion > 0.5)) ||
(!rangefinder_state_in_range && wp_proportion >= 1) ||
probably_crashed) {
const AP_GPS &gps = AP::gps();
if (type_slope_stage != SLOPE_STAGE_FINAL) {
type_slope_flags.post_stats = true;
if (is_flying && (AP_HAL::millis()-last_flying_ms) > 3000) {
@ -156,6 +157,17 @@ bool AP_Landing::type_slope_verify_land(const Location &prev_WP_loc, Location &n
disarm_if_autoland_complete_fn();
}
if (mission.continue_after_land() &&
type_slope_stage == SLOPE_STAGE_FINAL &&
gps.status() >= AP_GPS::GPS_OK_FIX_3D &&
gps.ground_speed() < 1) {
/*
user has requested to continue with mission after a
landing. Return true to allow for continue
*/
return true;
}
/*
we return false as a landing mission item never completes