mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Compass: rename AP_AHRS::get_position to get_location
This commit is contained in:
parent
84e58c4f7f
commit
38abec2133
@ -1718,7 +1718,7 @@ void Compass::try_set_initial_location()
|
||||
}
|
||||
|
||||
Location loc;
|
||||
if (!AP::ahrs().get_position(loc)) {
|
||||
if (!AP::ahrs().get_location(loc)) {
|
||||
return;
|
||||
}
|
||||
_initial_location_set = true;
|
||||
|
@ -489,7 +489,7 @@ MAV_RESULT Compass::mag_cal_fixed_yaw(float yaw_deg, uint8_t compass_mask,
|
||||
if (is_zero(lat_deg) && is_zero(lon_deg)) {
|
||||
Location loc;
|
||||
// get AHRS position. If unavailable then try GPS location
|
||||
if (!AP::ahrs().get_position(loc)) {
|
||||
if (!AP::ahrs().get_location(loc)) {
|
||||
if (AP::gps().status() < AP_GPS::GPS_OK_FIX_3D) {
|
||||
gcs().send_text(MAV_SEVERITY_ERROR, "Mag: no position available");
|
||||
return MAV_RESULT_FAILED;
|
||||
|
Loading…
Reference in New Issue
Block a user