mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: NavEKF: make set_origin and get_origin WARN_IF_UNUSED as base class
This commit is contained in:
parent
cea0d7c971
commit
d2278fb525
|
@ -151,10 +151,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
|
||||
bool set_origin(const Location &loc) override;
|
||||
bool set_origin(const Location &loc) override WARN_IF_UNUSED;
|
||||
|
||||
// returns the inertial navigation origin in lat/lon/alt
|
||||
bool get_origin(Location &ret) const override;
|
||||
bool get_origin(Location &ret) const override WARN_IF_UNUSED;
|
||||
|
||||
bool have_inertial_nav() const override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue