ArduCopter: move setting of land's yaw mode to the do_land function

This commit is contained in:
Randy Mackay 2013-01-12 14:49:26 +09:00
parent 05e59f6f4d
commit 36f15c9555

View File

@ -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(&current_loc);
wp_control = LOITER_MODE;
// hold current heading
set_yaw_mode(YAW_HOLD);
set_throttle_mode(THROTTLE_LAND);
}