mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: Use new Location::same_loc_as() function
This commit is contained in:
parent
76e8407297
commit
6a2bfeb3dd
@ -821,12 +821,7 @@ bool Plane::get_target_location(Location& target_loc)
|
|||||||
*/
|
*/
|
||||||
bool Plane::update_target_location(const Location &old_loc, const Location &new_loc)
|
bool Plane::update_target_location(const Location &old_loc, const Location &new_loc)
|
||||||
{
|
{
|
||||||
if (!old_loc.same_latlon_as(next_WP_loc)) {
|
if (!old_loc.same_loc_as(next_WP_loc)) {
|
||||||
return false;
|
|
||||||
}
|
|
||||||
ftype alt_diff;
|
|
||||||
if (!old_loc.get_alt_distance(next_WP_loc, alt_diff) ||
|
|
||||||
!is_zero(alt_diff)) {
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
next_WP_loc = new_loc;
|
next_WP_loc = new_loc;
|
||||||
|
Loading…
Reference in New Issue
Block a user