Plane: Disallow arming if quadplane has been requested but isn't available

This commit is contained in:
Michael du Breuil 2018-12-24 02:06:22 -07:00 committed by Andrew Tridgell
parent fc2b43313e
commit 69c87c6c4a
2 changed files with 8 additions and 0 deletions

View File

@ -53,6 +53,11 @@ bool AP_Arming_Plane::pre_arm_checks(bool display_failure)
ret = false;
}
if (plane.quadplane.enabled() && !plane.quadplane.available()) {
check_failed(ARMING_CHECK_NONE, display_failure, "Quadplane enabled but not running");
ret = false;
}
if (plane.quadplane.available() && plane.scheduler.get_loop_rate_hz() < 100) {
check_failed(ARMING_CHECK_NONE, display_failure, "quadplane needs SCHED_LOOP_RATE >= 100");
ret = false;

View File

@ -116,6 +116,9 @@ public:
// return true if the wp_nav controller is being updated
bool using_wp_nav(void) const;
// return true if the user has set ENABLE
bool enabled(void) const { return enable != 0; }
struct PACKED log_QControl_Tuning {
LOG_PACKET_HEADER;