From 3618ac62e040fd98011e793e4e1f89f9b448de80 Mon Sep 17 00:00:00 2001
From: rmackay9 <rmackay9@yahoo.com>
Date: Wed, 13 Jun 2012 21:50:16 +0900
Subject: [PATCH] ArduCopter: made Robert's new yaw method optional (off by
 default).

Add this line to APM_Config.h to enable Robert's yaw
#define ALTERNATIVE_YAW_MODE ENABLED
---
 ArduCopter/Attitude.pde | 14 ++++++++++++++
 ArduCopter/config.h     |  4 ++++
 2 files changed, 18 insertions(+)

diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde
index 0b210c5be..b53b27ad8 100644
--- a/ArduCopter/Attitude.pde
+++ b/ArduCopter/Attitude.pde
@@ -409,9 +409,23 @@ get_nav_yaw_offset(int yaw_input, int reset)
 		return ahrs.yaw_sensor;
 
 	}else{
+#if ALTERNATIVE_YAW_MODE == ENABLED
 		_yaw = nav_yaw + (yaw_input / 50);
 		return wrap_360(_yaw);
+#else
+		// re-define nav_yaw if we have stick input
+		if(yaw_input != 0){
+			// set nav_yaw + or - the current location
+			_yaw = yaw_input + ahrs.yaw_sensor;
+			// we need to wrap our value so we can be 0 to 360 (*100)
+			return wrap_360(_yaw);
+
+		}else{
+			// no stick input, lets not change nav_yaw
+			return nav_yaw;
 		}
+#endif
+	}
 }
 
 static int16_t get_angle_boost(int16_t value)
diff --git a/ArduCopter/config.h b/ArduCopter/config.h
index 6db23de25..89c6ecf00 100644
--- a/ArduCopter/config.h
+++ b/ArduCopter/config.h
@@ -989,4 +989,8 @@
 # define RETRO_LOITER_MODE DISABLED
 #endif
 
+#ifndef ALTERNATIVE_YAW_MODE
+# define ALTERNATIVE_YAW_MODE DISABLED
+#endif
+
 #endif // __ARDUCOPTER_CONFIG_H__
-- 
GitLab