From e8ab4eb8b7f03fefa8190afb434d695120c0d34f Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 17 Jun 2022 15:57:24 +0900 Subject: [PATCH] AP_Mount: SToRM32_serial provides calc_angle_to_xxx relative_pan argument --- libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp index 8c2f5d22f2..5cd75c6fa4 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32_serial.cpp @@ -76,7 +76,7 @@ void AP_Mount_SToRM32_serial::update() // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)) { resend_now = true; } break; @@ -88,15 +88,13 @@ void AP_Mount_SToRM32_serial::update() } _state._roi_target = AP::ahrs().get_home(); _state._roi_target_set = true; - if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true)) { + if (calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)) { resend_now = true; } break; case MAV_MOUNT_MODE_SYSID_TARGET: - if (calc_angle_to_sysid_target(_angle_ef_target_rad, - true, - true)) { + if (calc_angle_to_sysid_target(_angle_ef_target_rad, true, true, true)) { resend_now = true; } break;