AP_NavEKF2: fixed inverted function setInhibitGpsVertVelUse()

This commit is contained in:
Andrew Tridgell 2017-10-22 14:34:05 +11:00 committed by Randy Mackay
parent f7db538220
commit 4019a167a9
1 changed files with 1 additions and 1 deletions

View File

@ -134,7 +134,7 @@ public:
// Set the argument to true to prevent the EKF using the GPS vertical velocity
// This can be used for situations where GPS velocity errors are causing problems with height accuracy
void setGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
void setInhibitGpsVertVelUse(const bool varIn) { inhibitGpsVertVelUse = varIn; };
// return the horizontal speed limit in m/s set by optical flow sensor limits
// return the scale factor to be applied to navigation velocity gains to compensate for increase in velocity noise with height when using optical flow