Plane: added an arming check for Q_ASSIST_SPEED

Q_ASSIST should really be enabled for all non-tailsitter
quadplanes. This arming check will help users remember to configure it
This commit is contained in:
Andrew Tridgell 2022-03-16 06:48:06 +11:00
parent a19fa24ccd
commit a1856c5c22
2 changed files with 11 additions and 1 deletions

View File

@ -174,6 +174,16 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
}
}
/*
Q_ASSIST_SPEED really should be enabled for all quadplanes except tailsitters
*/
if (check_enabled(ARMING_CHECK_PARAMETERS) &&
is_zero(plane.quadplane.assist_speed) &&
!plane.quadplane.tailsitter.enabled()) {
check_failed(display_failure,"Q_ASSIST_SPEED is not set");
ret = false;
}
return ret;
}
#endif // HAL_QUADPLANE_ENABLED

View File

@ -103,7 +103,7 @@ const AP_Param::GroupInfo QuadPlane::var_info[] = {
// @Param: ASSIST_SPEED
// @DisplayName: Quadplane assistance speed
// @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. Zero means no assistance except during transition
// @Description: This is the speed below which the quad motors will provide stability and lift assistance in fixed wing modes. Zero means no assistance except during transition. Note that if this is set to zero then other Q_ASSIST features are also disabled. A higher value will lead to more false positives which can waste battery. A lower value will result in less false positive, but will result in assistance taking longer to trigger. If unsure then set to 3 m/s below the minimum airspeed you will fly at. If you don't have an airspeed sensor then use 5 m/s below the minimum airspeed you fly at. If you want to disable the arming check Q_ASSIST_SPEED then set to -1.
// @Units: m/s
// @Range: 0 100
// @Increment: 0.1