mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: avoid using struct Location
clang reports this could be a problem when compiling under some EABIs. Remove it from most places as it is just noise, replace with class where we want to avoid including Location.h
This commit is contained in:
parent
86d2f07f3d
commit
44d0172f83
|
@ -206,7 +206,7 @@ bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point) co
|
|||
|
||||
bool AC_PolyFence_loader::breached() const
|
||||
{
|
||||
struct Location loc;
|
||||
Location loc;
|
||||
if (!AP::ahrs().get_location(loc)) {
|
||||
return false;
|
||||
}
|
||||
|
@ -648,7 +648,7 @@ bool AC_PolyFence_loader::load_from_eeprom()
|
|||
return _load_time_ms != 0;
|
||||
}
|
||||
|
||||
struct Location ekf_origin{};
|
||||
Location ekf_origin{};
|
||||
if (!AP::ahrs().get_origin(ekf_origin)) {
|
||||
// Debug("fence load requires origin");
|
||||
return false;
|
||||
|
|
Loading…
Reference in New Issue