mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: fixed warning on WARN_IF_UNUSED
This commit is contained in:
parent
5eb9622105
commit
6622a4579e
|
@ -364,7 +364,7 @@ public:
|
|||
|
||||
// return a Down position relative to home in meters
|
||||
// if EKF is unavailable will return the baro altitude
|
||||
virtual void get_relative_position_D_home(float &posD) const WARN_IF_UNUSED = 0;
|
||||
virtual void get_relative_position_D_home(float &posD) const = 0;
|
||||
|
||||
// return a Down position relative to origin in meters
|
||||
// Return true if estimate is valid
|
||||
|
|
Loading…
Reference in New Issue