From 98dfaba23d1c2af19e374c0107531cbf87ad43b4 Mon Sep 17 00:00:00 2001 From: Nick Exton Date: Mon, 16 Oct 2023 15:10:04 +1100 Subject: [PATCH] Copter: Use AP_Mount::clear_roi_target() to remove ROI --- ArduCopter/autoyaw.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/ArduCopter/autoyaw.cpp b/ArduCopter/autoyaw.cpp index 3254dfde78..40acda0f05 100644 --- a/ArduCopter/autoyaw.cpp +++ b/ArduCopter/autoyaw.cpp @@ -154,9 +154,7 @@ void Mode::AutoYaw::set_roi(const Location &roi_location) auto_yaw.set_mode_to_default(false); #if HAL_MOUNT_ENABLED // switch off the camera tracking if enabled - if (copter.camera_mount.get_mode() == MAV_MOUNT_MODE_GPS_POINT) { - copter.camera_mount.set_mode_to_default(); - } + copter.camera_mount.clear_roi_target(); #endif // HAL_MOUNT_ENABLED } else { #if HAL_MOUNT_ENABLED