AP_Mount: fixed longitude subtraction

This commit is contained in:
Andrew Tridgell 2021-06-24 06:43:50 +10:00
parent 51a3bc170b
commit 86e8731fc5

View File

@ -185,7 +185,7 @@ bool AP_Mount_Backend::calc_angle_to_location(const struct Location &target, Vec
if (!AP::ahrs().get_position(current_loc)) {
return false;
}
const float GPS_vector_x = (target.lng-current_loc.lng)*cosf(ToRad((current_loc.lat+target.lat)*0.00000005f))*0.01113195f;
const float GPS_vector_x = Location::diff_longitude(target.lng,current_loc.lng)*cosf(ToRad((current_loc.lat+target.lat)*0.00000005f))*0.01113195f;
const float GPS_vector_y = (target.lat-current_loc.lat)*0.01113195f;
int32_t target_alt_cm = 0;
if (!target.get_alt_cm(Location::AltFrame::ABOVE_HOME, target_alt_cm)) {