mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AC_Fence: correct fence upload reload boundary trigger
The check in AC_Fence::check_fence_polygon is for boundary points, not boundary loaded
This commit is contained in:
parent
194142b343
commit
434f22cf40
@ -498,7 +498,7 @@ void AC_Fence::handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg)
|
||||
link.send_text(MAV_SEVERITY_WARNING, "Failed to save polygon point, too many points?");
|
||||
} else {
|
||||
// trigger reload of points
|
||||
_boundary_loaded = false;
|
||||
_boundary_num_points = 0;
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
Loading…
Reference in New Issue
Block a user