Skip to content

Commit

Permalink
Sub: Use AP_Mount::clear_roi_target() to remove ROI
Browse files Browse the repository at this point in the history
  • Loading branch information
nexton-winjeel committed Oct 18, 2023
1 parent 868fef3 commit 44ee5cd
Showing 1 changed file with 1 addition and 3 deletions.
4 changes: 1 addition & 3 deletions ArduSub/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down

0 comments on commit 44ee5cd

Please sign in to comment.