AC_Fence: check the return value of fetching the EKF origin

This commit is contained in:
Michael du Breuil 2019-03-11 14:06:56 -07:00 committed by Randy Mackay
parent cbb0bfb809
commit 281d3b1189

View File

@ -550,7 +550,9 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
return false;
}
struct Location ekf_origin {};
AP::ahrs().get_origin(ekf_origin);
if (!AP::ahrs().get_origin(ekf_origin)) {
return false;
}
// sanity check total
_total = constrain_int16(_total, 0, _poly_loader.max_points());