AP_AHRS: AP_AHRS gets a virtual get_hagl function, EKF marks it override

This commit is contained in:
Peter Barker 2018-01-06 12:25:04 +11:00 committed by Francisco Ferreira
parent 0862d1454e
commit 659ab06d3b
2 changed files with 3 additions and 1 deletions

View File

@ -303,6 +303,8 @@ public:
// otherwise false. This call fills in lat, lng and alt
virtual bool get_position(struct Location &loc) const = 0;
virtual bool get_hagl(float &height) const { return false; }
// return a wind estimation vector, in m/s
virtual Vector3f wind_estimate(void) const = 0;

View File

@ -72,7 +72,7 @@ public:
bool get_position(struct Location &loc) const override;
// get latest altitude estimate above ground level in meters and validity flag
bool get_hagl(float &hagl) const;
bool get_hagl(float &hagl) const override;
// status reporting of estimated error
float get_error_rp() const override;