AP_Common: Include altitude in the init check for a location

This commit is contained in:
Michael du Breuil 2019-09-12 18:02:36 -07:00 committed by Andrew Tridgell
parent 9eb6c1be64
commit 819d1b5246

View File

@ -112,7 +112,7 @@ public:
*/
float line_path_proportion(const Location &point1, const Location &point2) const;
bool initialised() const { return (lat !=0 || lng != 0); }
bool initialised() const { return (lat !=0 || lng != 0 || alt != 0); }
private:
static AP_Terrain *_terrain;