diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 491d89d79f..3db9d6ae9e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -434,6 +434,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = { // @Path: ../libraries/AC_AttitudeControl/AC_WeatherVane.cpp AP_SUBGROUPPTR(weathervane, "WVANE_", 30, QuadPlane, AC_WeatherVane), + // @Param: LAND_ALTCHG + // @DisplayName: Land detection altitude change threshold + // @Description: The maximum altitude change allowed during land detection. You can raise this value if you find that landing detection takes a long time to complete. It is the maximum change in altitude over a period of 4 seconds for landing to be detected + // @Units: m + // @Range: 0.1 0.6 + // @Increment: 0.05 + // @User: Standard + AP_GROUPINFO("LAND_ALTCHG", 31, QuadPlane, landing_detect.detect_alt_change, 0.2), + AP_GROUPEND }; @@ -2991,7 +3000,7 @@ bool QuadPlane::land_detector(uint32_t timeout_ms) // we only consider the vehicle landed when the motors have been // at minimum for timeout_ms+1000 and the vertical position estimate has not // changed by more than 20cm for timeout_ms - if (fabsf(height - landing_detect.vpos_start_m) > 0.2) { + if (fabsf(height - landing_detect.vpos_start_m) > landing_detect.detect_alt_change) { // height has changed, call off landing detection landing_detect.land_start_ms = 0; return false; diff --git a/ArduPlane/quadplane.h b/ArduPlane/quadplane.h index d20404d1ff..7b184afc00 100644 --- a/ArduPlane/quadplane.h +++ b/ArduPlane/quadplane.h @@ -402,6 +402,9 @@ private: uint32_t lower_limit_start_ms; uint32_t land_start_ms; float vpos_start_m; + + // landing detection threshold in meters + AP_Float detect_alt_change; } landing_detect; // throttle mix acceleration filter