mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: Keep FIXED mode when WP_YAW_BEHAVIOR is NONE
This commit is contained in:
parent
77f1efac5e
commit
63663303de
@ -449,7 +449,7 @@ bool ModeAuto::wp_start(const Location& dest_loc)
|
|||||||
|
|
||||||
// initialise yaw
|
// initialise yaw
|
||||||
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
|
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
|
||||||
if (auto_yaw.mode() != AutoYaw::Mode::ROI) {
|
if (auto_yaw.mode() != AutoYaw::Mode::ROI && !(auto_yaw.mode() == AutoYaw::Mode::FIXED && copter.g.wp_yaw_behavior == WP_YAW_BEHAVIOR_NONE)) {
|
||||||
auto_yaw.set_mode_to_default(false);
|
auto_yaw.set_mode_to_default(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -1804,7 +1804,7 @@ void ModeAuto::do_spline_wp(const AP_Mission::Mission_Command& cmd)
|
|||||||
|
|
||||||
// initialise yaw
|
// initialise yaw
|
||||||
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
|
// To-Do: reset the yaw only when the previous navigation command is not a WP. this would allow removing the special check for ROI
|
||||||
if (auto_yaw.mode() != AutoYaw::Mode::ROI) {
|
if (auto_yaw.mode() != AutoYaw::Mode::ROI && !(auto_yaw.mode() == AutoYaw::Mode::FIXED && copter.g.wp_yaw_behavior == WP_YAW_BEHAVIOR_NONE)) {
|
||||||
auto_yaw.set_mode_to_default(false);
|
auto_yaw.set_mode_to_default(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user