diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index b6040be36f5457a32c539440177cf7b754999ebe..2425eae8ff54fe6dd566570a475edc668c68bee8 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -17,7 +17,6 @@ static void process_nav_command() break; case MAV_CMD_NAV_LAND: // 21 LAND to Waypoint - set_yaw_mode(YAW_HOLD); do_land(); break; @@ -292,6 +291,9 @@ static void do_land() set_next_WP(¤t_loc); wp_control = LOITER_MODE; + // hold current heading + set_yaw_mode(YAW_HOLD); + set_throttle_mode(THROTTLE_LAND); }