@ -434,6 +434,15 @@ const AP_Param::GroupInfo QuadPlane::var_info2[] = {
@@ -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
} ;
@ -2995,7 +3004,7 @@ bool QuadPlane::land_detector(uint32_t timeout_ms)
@@ -2995,7 +3004,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 ;