mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_AHRS: add get_origin method to parent
This commit is contained in:
parent
7257fb6284
commit
82cd320bd0
@ -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 {
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user