mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_AHRS: Warn if the return value on (get, set)_origin is not checked
This commit is contained in:
parent
281d3b1189
commit
0bf2fc004e
@ -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();
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user