From 36f15c9555f7c4f54d2d82901d141f2a2fe392ec Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Sat, 12 Jan 2013 14:49:26 +0900
Subject: [PATCH] ArduCopter: move setting of land's yaw mode to the do_land
 function

---
 ArduCopter/commands_logic.pde | 4 +++-
 1 file changed, 3 insertions(+), 1 deletion(-)

diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde
index b6040be36..2425eae8f 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(&current_loc);
     wp_control = LOITER_MODE;
 
+    // hold current heading
+    set_yaw_mode(YAW_HOLD);
+
     set_throttle_mode(THROTTLE_LAND);
 }
 
-- 
GitLab