diff --git a/libraries/AP_NavEKF3/AP_NavEKF3.h b/libraries/AP_NavEKF3/AP_NavEKF3.h index e221294670..f5617fcd9e 100644 --- a/libraries/AP_NavEKF3/AP_NavEKF3.h +++ b/libraries/AP_NavEKF3/AP_NavEKF3.h @@ -129,7 +129,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