|
|
|
@ -163,10 +163,15 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
@@ -163,10 +163,15 @@ bool AP_Arming_Plane::quadplane_checks(bool display_failure)
|
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
if (((plane.quadplane.options & QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO) != 0) && |
|
|
|
|
!plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto) && (plane.control_mode != &plane.mode_guided)) { |
|
|
|
|
check_failed(display_failure,"not in Q mode"); |
|
|
|
|
ret = false; |
|
|
|
|
if ((plane.quadplane.options & QuadPlane::OPTION_ONLY_ARM_IN_QMODE_OR_AUTO) != 0) { |
|
|
|
|
if (!plane.control_mode->is_vtol_mode() && (plane.control_mode != &plane.mode_auto) && (plane.control_mode != &plane.mode_guided)) { |
|
|
|
|
check_failed(display_failure,"not in Q mode"); |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
if ((plane.control_mode == &plane.mode_auto) && !plane.quadplane.is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) { |
|
|
|
|
check_failed(display_failure,"not in VTOL takeoff"); |
|
|
|
|
ret = false; |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
return ret; |
|
|
|
|