From 3a5807ae564086726265b6a6ef12f1c258962d3e Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 16 Mar 2018 12:04:49 +1100 Subject: [PATCH] AP_AHRS: move home_status into AP_AHRS Storing home in the AHRS object but not its state is clearly evil. Fix that. --- libraries/AP_AHRS/AP_AHRS.h | 13 +++++++++++++ 1 file changed, 13 insertions(+) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index 75d1cc167f..2694b06321 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -462,6 +462,16 @@ public: return _home; } + enum HomeState home_status(void) const { + return _home_status; + } + void set_home_status(enum HomeState new_status) { + _home_status = new_status; + } + bool home_is_set(void) const { + return _home_status != HOME_UNSET; + } + // set the home location in 10e7 degrees. This should be called // when the vehicle is at this position. It is assumed that the // current barometer and GPS altitudes correspond to this altitude @@ -673,6 +683,9 @@ protected: private: static AP_AHRS *_singleton; + // Flag for if we have g_gps lock and have set the home location in AHRS + enum HomeState _home_status = HOME_UNSET; + }; #include "AP_AHRS_DCM.h"