mirror of https://github.com/ArduPilot/ardupilot
Plane: check for VTOL takeoff in AUTO
if the "only arm in Q modes" bit is set in Q_OPTIONS then check that in AUTO mode we are in a VTOL takeoff WP
This commit is contained in:
parent
dd6ce1fa73
commit
1c89b7f3a2
|
@ -163,11 +163,16 @@ 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)) {
|
||||
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;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue