mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-03 06:28:32 -04:00
ArduCopter: restore YAW to default AUTO_YAW mode instead of YAW_LOOK_AT_NEXT_WP mode
This commit is contained in:
parent
66133f4e59
commit
31fd9a22a3
@ -285,9 +285,9 @@ static void do_nav_wp()
|
|||||||
wp_verify_byte |= NAV_ALTITUDE;
|
wp_verify_byte |= NAV_ALTITUDE;
|
||||||
}
|
}
|
||||||
|
|
||||||
// reset control of yaw
|
// reset control of yaw to default
|
||||||
if( g.yaw_override_behaviour == YAW_OVERRIDE_BEHAVIOUR_AT_NEXT_WAYPOINT ) {
|
if( g.yaw_override_behaviour == YAW_OVERRIDE_BEHAVIOUR_AT_NEXT_WAYPOINT ) {
|
||||||
set_yaw_mode(YAW_LOOK_AT_NEXT_WP);
|
set_yaw_mode(AUTO_YAW);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user