From 05e72c6e6808a4f9e53067ec88b7a179009b561d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 12 Sep 2012 09:57:54 +1000 Subject: [PATCH] APM: fixed roll in landing approach --- ArduPlane/ArduPlane.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 68a0f80eda..830be466e2 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1105,7 +1105,7 @@ static void update_current_flight_mode(void) break; case MAV_CMD_NAV_LAND: - if (g.rudder_steer == 0) { + if (g.rudder_steer == 0 || !land_complete) { calc_nav_roll(); } else { nav_roll_cd = 0;