diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp index 051f439017..b03b103431 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.cpp @@ -125,7 +125,7 @@ float AP_InertialNav_NavEKF::get_altitude() const * * @return */ -bool AP_InertialNav_NavEKF::get_hagl(float height) const +bool AP_InertialNav_NavEKF::get_hagl(float &height) const { // true when estimate is valid bool valid = _ahrs_ekf.get_NavEKF().getHAGL(height); diff --git a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h index c5c5af18a3..e64e342270 100644 --- a/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h +++ b/libraries/AP_InertialNav/AP_InertialNav_NavEKF.h @@ -92,7 +92,7 @@ public: * getHgtAboveGnd - get latest altitude estimate above ground level in centimetres and validity flag * @return */ - bool get_hagl(float hagl) const; + bool get_hagl(float &hagl) const; /** * get_hgt_ctrl_limit - get maximum height to be observed by the control loops in cm and a validity flag