From 57a508b0375b2568941bbb586a294a1757a11373 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 17 Jun 2022 15:56:53 +0900 Subject: [PATCH] AP_Mount: Solo provides calc_angle_to_xxx relative_pan argument --- libraries/AP_Mount/AP_Mount_SoloGimbal.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp index cd271f8fe5..07a18e0c46 100644 --- a/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp +++ b/libraries/AP_Mount/AP_Mount_SoloGimbal.cpp @@ -69,7 +69,7 @@ void AP_Mount_SoloGimbal::update() // point mount to a GPS point given by the mission planner case MAV_MOUNT_MODE_GPS_POINT: _gimbal.set_lockedToBody(false); - UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true)); + UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)); break; case MAV_MOUNT_MODE_HOME_LOCATION: @@ -80,11 +80,11 @@ void AP_Mount_SoloGimbal::update() _state._roi_target = AP::ahrs().get_home(); _state._roi_target_set = true; _gimbal.set_lockedToBody(false); - UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true)); + UNUSED_RESULT(calc_angle_to_roi_target(_angle_ef_target_rad, true, true, true)); break; case MAV_MOUNT_MODE_SYSID_TARGET: - UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true)); + UNUSED_RESULT(calc_angle_to_sysid_target(_angle_ef_target_rad, true, true, true)); break; default: