AP_L1_Control: 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 51a9efe817
commit cd88ec65fa
1 changed files with 2 additions and 2 deletions

View File

@ -217,7 +217,7 @@ void AP_L1_Control::update_waypoint(const struct Location &prev_WP, const struct
float K_L1 = 4.0f * _L1_damping * _L1_damping;
// Get current position and velocity
if (_ahrs.get_position(_current_loc) == false) {
if (_ahrs.get_location(_current_loc) == false) {
// if no GPS loc available, maintain last nav/target_bearing
_data_is_stale = true;
return;
@ -349,7 +349,7 @@ void AP_L1_Control::update_loiter(const struct Location &center_WP, float radius
float K_L1 = 4.0f * _L1_damping * _L1_damping;
//Get current position and velocity
if (_ahrs.get_position(_current_loc) == false) {
if (_ahrs.get_location(_current_loc) == false) {
// if no GPS loc available, maintain last nav/target_bearing
_data_is_stale = true;
return;