mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
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
This commit is contained in:
parent
f829f5615b
commit
6e78d2af5a
@ -2387,10 +2387,6 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude)
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Must be armed for takeoff");
|
||||
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()) {
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Already flying - no takeoff");
|
||||
return false;
|
||||
|
Loading…
Reference in New Issue
Block a user