From 3edd95b99b5e0b5ff9ece8488c53c3fda8f95317 Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Sun, 10 Jul 2016 15:41:20 -0700 Subject: [PATCH] AP_Common: add Location::is_zero and ::zero member functions --- libraries/AP_Common/Location.cpp | 3 +-- libraries/AP_Common/Location.h | 4 ++++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index 187416651a..ad4e95c0cb 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -20,8 +20,7 @@ AP_Terrain *Location_Class::_terrain = NULL; /// constructors Location_Class::Location_Class() { - lat = lng = alt = 0; - options = 0; + zero(); } Location_Class::Location_Class(int32_t latitude, int32_t longitude, int32_t alt_in_cm, ALT_FRAME frame) diff --git a/libraries/AP_Common/Location.h b/libraries/AP_Common/Location.h index dac697968f..bfd61436ce 100644 --- a/libraries/AP_Common/Location.h +++ b/libraries/AP_Common/Location.h @@ -67,6 +67,10 @@ public: // extrapolate latitude/longitude given distances (in meters) north and east void offset(float ofs_north, float ofs_east); + bool is_zero(void) { return (lat == 0 && lng == 0 && alt == 0 && options == 0); } + + void zero(void) { lat = lng = alt = 0; options = 0; } + private: static const AP_AHRS_NavEKF *_ahrs; static AP_Terrain *_terrain;