AP_AHRS: Warn if the return value on (get, set)_origin is not checked

This commit is contained in:
Michael du Breuil 2019-03-11 14:07:24 -07:00 committed by Randy Mackay
parent 281d3b1189
commit 0bf2fc004e

View File

@ -470,10 +470,10 @@ public:
// 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
virtual bool set_origin(const Location &loc) { return false; }
virtual bool set_origin(const Location &loc) WARN_IF_UNUSED { return false; }
// returns the inertial navigation origin in lat/lon/alt
virtual bool get_origin(Location &ret) const { return false; }
virtual bool get_origin(Location &ret) const WARN_IF_UNUSED { return false; }
void Log_Write_Home_And_Origin();