Plane: cope with QGC retrying AUTO mode

QGC tries several times to enter AUTO even when it is refused. We need
to keep refusing
This commit is contained in:
Andrew Tridgell 2022-05-18 21:50:17 +10:00
parent 80c27a426c
commit d4146a1672
1 changed files with 1 additions and 0 deletions

View File

@ -10,6 +10,7 @@ bool ModeAuto::_enter()
quadplane.guided_wait_takeoff_on_mode_enter) {
if (!plane.mission.starts_with_takeoff_cmd()) {
gcs().send_text(MAV_SEVERITY_ERROR,"Takeoff waypoint required");
quadplane.guided_wait_takeoff = true;
return false;
}
}