diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 0280ee3869..083016c557 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -103,7 +103,7 @@ Location::AltFrame Location::get_alt_frame() const bool Location::get_alt_cm(AltFrame desired_frame, int32_t &ret_alt_cm) const { #if CONFIG_HAL_BOARD == HAL_BOARD_SITL - if (lat == 0 && lng == 0) { + if (!initialised()) { AP_HAL::panic("Should not be called on invalid location"); } #endif diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index 6cea7b369f..a881e0e541 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -112,6 +112,8 @@ public: */ float line_path_proportion(const Location &point1, const Location &point2) const; + bool initialised() const { return (lat !=0 || lng != 0); } + private: static AP_Terrain *_terrain;