From 44ee5cdabd3afa83eed77d058145e430dbbccbe7 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Mon, 16 Oct 2023 15:09:51 +1100 Subject: [PATCH] Sub: Use AP_Mount::clear_roi_target() to remove ROI --- ArduSub/mode_auto.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduSub/mode_auto.cpp b/ArduSub/mode_auto.cpp index 87ad912976b5c..d947c8ed0e938 100644 --- a/ArduSub/mode_auto.cpp +++ b/ArduSub/mode_auto.cpp @@ -394,9 +394,7 @@ void ModeAuto::set_auto_yaw_roi(const Location &roi_location) set_auto_yaw_mode(get_default_auto_yaw_mode(false)); #if HAL_MOUNT_ENABLED // switch off the camera tracking if enabled - if (sub.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) { - sub.camera_mount.set_mode_to_default(); - } + sub.camera_mount.clear_roi_target(); #endif // HAL_MOUNT_ENABLED } else { #if HAL_MOUNT_ENABLED