Copter: auto's wp_start skips submode change on terrain failsafe

This commit is contained in:
Randy Mackay 2021-01-29 16:25:29 +09:00
parent d981de1ff4
commit 238d102a56
1 changed files with 2 additions and 2 deletions

View File

@ -205,8 +205,6 @@ void ModeAuto::takeoff_start(const Location& dest_loc)
// auto_wp_start - initialises waypoint controller to implement flying to a particular destination
void ModeAuto::wp_start(const Location& dest_loc)
{
_mode = Auto_WP;
// send target to waypoint controller
if (!wp_nav->set_wp_destination_loc(dest_loc)) {
// failure to set destination can only be because of missing terrain data
@ -214,6 +212,8 @@ void ModeAuto::wp_start(const Location& dest_loc)
return;
}
_mode = Auto_WP;
// 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
if (auto_yaw.mode() != AUTO_YAW_ROI) {