mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_L1_Control: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
51a9efe817
commit
cd88ec65fa
@ -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;
|
float K_L1 = 4.0f * _L1_damping * _L1_damping;
|
||||||
|
|
||||||
// Get current position and velocity
|
// 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
|
// if no GPS loc available, maintain last nav/target_bearing
|
||||||
_data_is_stale = true;
|
_data_is_stale = true;
|
||||||
return;
|
return;
|
||||||
@ -349,7 +349,7 @@ void AP_L1_Control::update_loiter(const struct Location ¢er_WP, float radius
|
|||||||
float K_L1 = 4.0f * _L1_damping * _L1_damping;
|
float K_L1 = 4.0f * _L1_damping * _L1_damping;
|
||||||
|
|
||||||
//Get current position and velocity
|
//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
|
// if no GPS loc available, maintain last nav/target_bearing
|
||||||
_data_is_stale = true;
|
_data_is_stale = true;
|
||||||
return;
|
return;
|
||||||
|
Loading…
Reference in New Issue
Block a user