From a2e298bbfca1eecb478c62297cf675816b82cd78 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 14 May 2013 11:52:39 +0900 Subject: [PATCH] Copter: change to default RTL yaw behaviour We will not point the nose home for RTL but will point the nose for all other waypoints --- ArduCopter/config.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/config.h b/ArduCopter/config.h index a085a6b636..9cc9ccf3f4 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -585,7 +585,7 @@ // AUTO Mode // Note: Auto mode yaw behaviour is controlled by WP_YAW_BEHAVIOR parameter #ifndef WP_YAW_BEHAVIOR_DEFAULT - # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP + # define WP_YAW_BEHAVIOR_DEFAULT WP_YAW_BEHAVIOR_LOOK_AT_NEXT_WP_EXCEPT_RTL #endif #ifndef AUTO_RP