AP_Common: add Location::is_zero and ::zero member functions

This commit is contained in:
Tom Pittenger 2016-07-10 15:41:20 -07:00
parent 26efd90603
commit 3edd95b99b
2 changed files with 5 additions and 2 deletions

View File

@ -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)

View File

@ -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;