From 3cbb88ae20ccbcaa3e14b8a9d4c3e4c2f8791c91 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 23 May 2018 16:58:46 +1000 Subject: [PATCH] AP_AHRS: split home-set and home-locked state --- libraries/AP_AHRS/AP_AHRS.h | 19 +++++++++++-------- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 1 + libraries/AP_AHRS/AP_AHRS_NavEKF.cpp | 5 ----- libraries/AP_AHRS/AP_AHRS_NavEKF.h | 3 --- 4 files changed, 12 insertions(+), 16 deletions(-) diff --git a/libraries/AP_AHRS/AP_AHRS.h b/libraries/AP_AHRS/AP_AHRS.h index cd29d6db28..c1a8d62f0d 100644 --- a/libraries/AP_AHRS/AP_AHRS.h +++ b/libraries/AP_AHRS/AP_AHRS.h @@ -436,14 +436,18 @@ public: return _home; } - enum HomeState home_status(void) const { - return _home_status; + // functions to handle locking of home. Some vehicles use this to + // allow GCS to lock in a home location. + void lock_home() { + _home_locked = true; } - void set_home_status(enum HomeState new_status) { - _home_status = new_status; + bool home_is_locked() const { + return _home_locked; } + + // returns true if home is set bool home_is_set(void) const { - return _home_status != HOME_UNSET; + return _home_is_set; } // set the home location in 10e7 degrees. This should be called @@ -649,6 +653,8 @@ protected: // reference position for NED positions struct Location _home; + bool _home_is_set :1; + bool _home_locked :1; // helper trig variables float _cos_roll, _cos_pitch, _cos_yaw; @@ -667,9 +673,6 @@ 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" diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index e905140dad..c63f708c7b 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -1012,6 +1012,7 @@ void AP_AHRS_DCM::set_home(const Location &loc) { _home = loc; _home.options = 0; + _home_is_set = true; } // a relative ground position to home in meters, Down diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp index 900aa23b38..a68bb8a464 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.cpp @@ -587,11 +587,6 @@ Vector2f AP_AHRS_NavEKF::groundspeed_vector(void) } } -void AP_AHRS_NavEKF::set_home(const Location &loc) -{ - AP_AHRS_DCM::set_home(loc); -} - // set the EKF's origin location in 10e7 degrees. This should only // be called when the EKF has no absolute position reference (i.e. GPS) // from which to decide the origin on its own diff --git a/libraries/AP_AHRS/AP_AHRS_NavEKF.h b/libraries/AP_AHRS/AP_AHRS_NavEKF.h index cbf14af867..56d3789a18 100644 --- a/libraries/AP_AHRS/AP_AHRS_NavEKF.h +++ b/libraries/AP_AHRS/AP_AHRS_NavEKF.h @@ -125,9 +125,6 @@ public: // blended accelerometer values in the earth frame in m/s/s const Vector3f &get_accel_ef_blended() const override; - // set home location - void set_home(const Location &loc) override; - // set the EKF's origin location in 10e7 degrees. This should only // be called when the EKF has no absolute position reference (i.e. GPS) // from which to decide the origin on its own