From 870b9b0fbba55ebb659660240e39c358e3235cde Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Fri, 10 May 2013 10:46:17 +0900
Subject: [PATCH] Copter: only run nav controllers when auto-armed

This stops run-up in target position and nav controller I terms ahead of
throttle being raised
---
 ArduCopter/navigation.pde | 5 +++++
 1 file changed, 5 insertions(+)

diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde
index 77484872e..a483b6619 100644
--- a/ArduCopter/navigation.pde
+++ b/ArduCopter/navigation.pde
@@ -6,6 +6,11 @@ static void update_navigation()
 {
     static uint32_t nav_last_update = 0;        // the system time of the last time nav was run update
 
+    // exit immediately if not auto_armed
+    if (!ap.auto_armed) {
+        return;
+    }
+
     // check for inertial nav updates
     if( inertial_nav.position_ok() ) {
 
-- 
GitLab