From 287614b415f917b61b0a67f903c5a7399ce79b9d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 23 Jan 2017 10:37:16 +1100 Subject: [PATCH] Plane: fixed auto-takeoff throttle trigger for inverted launch quite an unusual setup, but has been done :-) --- ArduPlane/takeoff.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/takeoff.cpp b/ArduPlane/takeoff.cpp index b3b652d829..7704bc884d 100644 --- a/ArduPlane/takeoff.cpp +++ b/ArduPlane/takeoff.cpp @@ -61,7 +61,7 @@ bool Plane::auto_takeoff_check(void) // Check aircraft attitude for bad launch if (ahrs.pitch_sensor <= -3000 || ahrs.pitch_sensor >= 4500 || - labs(ahrs.roll_sensor) > 3000) { + (!fly_inverted() && labs(ahrs.roll_sensor) > 3000)) { gcs_send_text_fmt(MAV_SEVERITY_WARNING, "Bad launch AUTO"); goto no_launch; }