From 4019a167a92343686e8ad87311fef5b118de21d3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 22 Oct 2017 14:34:05 +1100 Subject: [PATCH] AP_NavEKF2: fixed inverted function setInhibitGpsVertVelUse() --- libraries/AP_NavEKF2/AP_NavEKF2.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.h b/libraries/AP_NavEKF2/AP_NavEKF2.h index 891f711d2b..733f9d3cd4 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.h +++ b/libraries/AP_NavEKF2/AP_NavEKF2.h @@ -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