diff --git a/ArduCopter/mode_circle.cpp b/ArduCopter/mode_circle.cpp index bb9a6612f948c..8e206845f2f97 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: