AP_AHRS: add get_origin method to parent

This commit is contained in:
Randy Mackay 2017-11-30 13:35:10 +09:00
parent 7257fb6284
commit 82cd320bd0
2 changed files with 4 additions and 1 deletions

View File

@ -478,6 +478,9 @@ public:
// from which to decide the origin on its own
virtual bool set_origin(const Location &loc) { return false; }
// returns the inertial navigation origin in lat/lon/alt
virtual bool get_origin(Location &ret) const { return false; }
// return true if the AHRS object supports inertial navigation,
// with very accurate position and velocity
virtual bool have_inertial_nav(void) const {

View File

@ -139,7 +139,7 @@ public:
bool set_origin(const Location &loc) override;
// returns the inertial navigation origin in lat/lon/alt
bool get_origin(Location &ret) const;
bool get_origin(Location &ret) const override;
bool have_inertial_nav() const override;