Plane: Use Location::same_loc_as() in QuadPlane::waypoint_controller()
This commit is contained in:
parent
6a2bfeb3dd
commit
674d7facde
@ -3044,8 +3044,7 @@ void QuadPlane::waypoint_controller(void)
|
|||||||
|
|
||||||
const Location &loc = plane.next_WP_loc;
|
const Location &loc = plane.next_WP_loc;
|
||||||
const uint32_t now = AP_HAL::millis();
|
const uint32_t now = AP_HAL::millis();
|
||||||
if (!loc.same_latlon_as(last_auto_target) ||
|
if (!loc.same_loc_as(last_auto_target) ||
|
||||||
plane.next_WP_loc.alt != last_auto_target.alt ||
|
|
||||||
now - last_loiter_ms > 500) {
|
now - last_loiter_ms > 500) {
|
||||||
wp_nav->set_wp_destination(poscontrol.target_cm.tofloat());
|
wp_nav->set_wp_destination(poscontrol.target_cm.tofloat());
|
||||||
last_auto_target = loc;
|
last_auto_target = loc;
|
||||||
|
Loading…
Reference in New Issue
Block a user