AC_WPNav: rename AP_AHRS::get_position to get_location

This commit is contained in:
Peter Barker 2022-01-21 10:42:40 +11:00 committed by Andrew Tridgell
parent 965b03f143
commit 05a5754452
1 changed files with 1 additions and 1 deletions

View File

@ -70,7 +70,7 @@ bool AC_WPNav_OA::update_wpnav()
// run path planning around obstacles
AP_OAPathPlanner *oa_ptr = AP_OAPathPlanner::get_singleton();
Location current_loc;
if ((oa_ptr != nullptr) && AP::ahrs().get_position(current_loc)) {
if ((oa_ptr != nullptr) && AP::ahrs().get_location(current_loc)) {
// backup _origin and _destination when not doing oa
if (_oa_state == AP_OAPathPlanner::OA_NOT_REQUIRED) {