AP_Mount: rename AP_AHRS::get_position to get_location

This commit is contained in:
Peter Barker 2022-01-21 10:42:41 +11:00 committed by Andrew Tridgell
parent 3f8fe9d3ef
commit fcd8d1b5eb

View File

@ -198,7 +198,7 @@ bool AP_Mount_Backend::calc_angle_to_sysid_target(Vector3f& angles_to_target_rad
bool AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vector3f& angles_to_target_rad, bool calc_tilt, bool calc_pan, bool relative_pan) const
{
Location current_loc;
if (!AP::ahrs().get_position(current_loc)) {
if (!AP::ahrs().get_location(current_loc)) {
return false;
}
const float GPS_vector_x = Location::diff_longitude(target.lng,current_loc.lng)*cosf(ToRad((current_loc.lat+target.lat)*0.00000005f))*0.01113195f;