AP_InertialNav: take reference to variable we are trying to update

There are no callers to this function.  Perhaps it should be removed?
This commit is contained in:
Peter Barker 2015-07-10 09:42:52 +10:00 committed by Andrew Tridgell
parent 818bb3f88f
commit 0028910428
2 changed files with 2 additions and 2 deletions

View File

@ -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);

View File

@ -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