From 954ffc272b9443c974591723acd925a0409f709d Mon Sep 17 00:00:00 2001 From: Paul Riseborough Date: Sun, 18 Aug 2024 08:02:51 +1000 Subject: [PATCH] Plane: Allow wind relative dead reckoning when lift motors are assisting When lift motors are assisting the wing during forward flight, the airspeed and zero sideslip assumption are still sufficiently valid to keep navigating. Without this patch a VTOL operating in FW mode without GPS and reliant on air data for dead reckoning will stop navigating and lose its position estimate if the lift motors start assisting. --- ArduPlane/Plane.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/ArduPlane/Plane.cpp b/ArduPlane/Plane.cpp index 1990ca0ed2e78..a487b0a724e7b 100644 --- a/ArduPlane/Plane.cpp +++ b/ArduPlane/Plane.cpp @@ -533,11 +533,6 @@ void Plane::update_fly_forward(void) ahrs.set_fly_forward(false); return; } - - if (quadplane.in_assisted_flight()) { - ahrs.set_fly_forward(false); - return; - } } #endif