AP_AHRS: mark get_hagl as WARN_IF_UNUSED

This commit is contained in:
Peter Barker 2020-12-06 21:59:00 +11:00 committed by Peter Barker
parent 8658023dad
commit 0fca126d06
2 changed files with 2 additions and 2 deletions

View File

@ -254,7 +254,7 @@ public:
virtual bool get_position(struct Location &loc) const = 0;
// get latest altitude estimate above ground level in meters and validity flag
virtual bool get_hagl(float &height) const { return false; }
virtual bool get_hagl(float &height) const WARN_IF_UNUSED { return false; }
// return a wind estimation vector, in m/s
virtual Vector3f wind_estimate(void) const = 0;

View File

@ -83,7 +83,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 override;
bool get_hagl(float &hagl) const override WARN_IF_UNUSED;
// status reporting of estimated error
float get_error_rp() const override;