mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
APM: fixed roll in landing approach
This commit is contained in:
parent
5f3ffe4839
commit
05e72c6e68
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user