ArduCopter: clarify frame of get_location_from_origin_offset

... by renaming it get_location_from_origin_offset_NED
This commit is contained in:
Peter Barker 2024-06-06 20:56:27 +10:00 committed by Peter Barker
parent 7ea2e60b5a
commit 72fa6aa410
1 changed files with 1 additions and 1 deletions

View File

@ -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: