From 72fa6aa4108ea0c84aecdce5537953628ad33365 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 6 Jun 2024 20:56:27 +1000 Subject: [PATCH] ArduCopter: clarify frame of get_location_from_origin_offset ... by renaming it get_location_from_origin_offset_NED --- ArduCopter/mode_circle.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index bb9a6612f9..8e206845f2 100644 --- a/ArduCopter/mode_circle.cpp +++ b/ArduCopter/mode_circle.cpp @@ -28,7 +28,7 @@ bool ModeCircle::init(bool ignore_checks) if (copter.circle_nav->roi_at_center()) { const Vector3p &pos { copter.circle_nav->get_center() }; Location circle_center; - if (!AP::ahrs().get_location_from_origin_offset(circle_center, pos * 0.01)) { + if (!AP::ahrs().get_location_from_origin_offset_NED(circle_center, pos * 0.01)) { return false; } // point at the ground: