mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-20 15:48:29 -04:00
AC_Fence: check the return value of fetching the EKF origin
This commit is contained in:
parent
cbb0bfb809
commit
281d3b1189
@ -550,7 +550,9 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
struct Location ekf_origin {};
|
struct Location ekf_origin {};
|
||||||
AP::ahrs().get_origin(ekf_origin);
|
if (!AP::ahrs().get_origin(ekf_origin)) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
// sanity check total
|
// sanity check total
|
||||||
_total = constrain_int16(_total, 0, _poly_loader.max_points());
|
_total = constrain_int16(_total, 0, _poly_loader.max_points());
|
||||||
|
Loading…
Reference in New Issue
Block a user