APM: fixed roll in landing approach

This commit is contained in:
Andrew Tridgell 2012-09-12 09:57:54 +10:00
parent 5f3ffe4839
commit 05e72c6e68
1 changed files with 1 additions and 1 deletions

View File

@ -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;