From 85b7f1bbb49fd1147a75aa9bb6e27b541f2566e8 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Mon, 11 Sep 2017 12:08:29 -0700 Subject: [PATCH] Plane: guided takeoff success should return true --- ArduPlane/quadplane.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/quadplane.cpp b/ArduPlane/quadplane.cpp index 8ede107de6..036f19f26e 100644 --- a/ArduPlane/quadplane.cpp +++ b/ArduPlane/quadplane.cpp @@ -2402,5 +2402,5 @@ bool QuadPlane::do_user_takeoff(float takeoff_altitude) motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); guided_start(); guided_takeoff = true; - return false; + return true; }