From 9135f01a9352841b83452bdab4a2a10128412a7a Mon Sep 17 00:00:00 2001 From: muramura Date: Sun, 16 Jun 2024 10:23:03 +0900 Subject: [PATCH] Copter: Move to the processing section to be used --- ArduCopter/mode_circle.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index 8e206845f2..2c31f8d0a3 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -22,8 +22,6 @@ bool ModeCircle::init(bool ignore_checks) copter.circle_nav->init(); #if HAL_MOUNT_ENABLED - AP_Mount *s = AP_Mount::get_singleton(); - // Check if the CIRCLE_OPTIONS parameter have roi_at_center if (copter.circle_nav->roi_at_center()) { const Vector3p &pos { copter.circle_nav->get_center() }; @@ -33,6 +31,7 @@ bool ModeCircle::init(bool ignore_checks) } // point at the ground: circle_center.set_alt_cm(0, Location::AltFrame::ABOVE_TERRAIN); + AP_Mount *s = AP_Mount::get_singleton(); s->set_roi_target(circle_center); } #endif