mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Mount: get_angle_target_to_location checks for valid location
This commit is contained in:
parent
41c319e257
commit
119c8b7363
@ -252,6 +252,11 @@ bool AP_Mount_Backend::get_angle_target_to_location(const Location &loc, MountTa
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// exit immediate if location is invalid
|
||||||
|
if (!loc.initialised()) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
const float GPS_vector_x = Location::diff_longitude(loc.lng, current_loc.lng)*cosf(ToRad((current_loc.lat + loc.lat) * 0.00000005f)) * 0.01113195f;
|
const float GPS_vector_x = Location::diff_longitude(loc.lng, current_loc.lng)*cosf(ToRad((current_loc.lat + loc.lat) * 0.00000005f)) * 0.01113195f;
|
||||||
const float GPS_vector_y = (loc.lat - current_loc.lat) * 0.01113195f;
|
const float GPS_vector_y = (loc.lat - current_loc.lat) * 0.01113195f;
|
||||||
int32_t target_alt_cm = 0;
|
int32_t target_alt_cm = 0;
|
||||||
|
Loading…
Reference in New Issue
Block a user