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
This commit is contained in:
Randy Mackay 2013-05-14 11:52:39 +09:00
parent 319f3ef560
commit a2e298bbfc
1 changed files with 1 additions and 1 deletions

View File

@ -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