Browse Source

AC_Fence: check the return value of fetching the EKF origin

master
Michael du Breuil 6 years ago committed by Randy Mackay
parent
commit
281d3b1189
  1. 4
      libraries/AC_Fence/AC_Fence.cpp

4
libraries/AC_Fence/AC_Fence.cpp

@ -550,7 +550,9 @@ bool AC_Fence::load_polygon_from_eeprom(bool force_reload) @@ -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());

Loading…
Cancel
Save