mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
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:
parent
319f3ef560
commit
a2e298bbfc
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user