Browse Source

Plane: allow takeoff in guided then fw loiter

this allows for quadplane takeoff in GUIDED with Q_GUIDED_MODE=0. The
takeoff will be VTOL, but subsequent guided points will be fixed wing
mission-4.1.18
Andrew Tridgell 7 years ago
parent
commit
35c1a732a6
  1. 4
      ArduPlane/quadplane.cpp

4
ArduPlane/quadplane.cpp

@ -2387,10 +2387,6 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
gcs().send_text(MAV_SEVERITY_INFO, "Must be armed for takeoff"); gcs().send_text(MAV_SEVERITY_INFO, "Must be armed for takeoff");
return false; return false;
} }
if (guided_mode == 0) {
gcs().send_text(MAV_SEVERITY_INFO, "Q_GUIDED_MODE must be set to 1");
return false;
}
if (is_flying()) { if (is_flying()) {
gcs().send_text(MAV_SEVERITY_INFO, "Already flying - no takeoff"); gcs().send_text(MAV_SEVERITY_INFO, "Already flying - no takeoff");
return false; return false;

Loading…
Cancel
Save