diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index d0c3fe8733..a043c20546 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -257,7 +257,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Param: EAS_NOISE // @DisplayName: Equivalent airspeed measurement noise (m/s) - // @Description: This is the RMS value of noise in equivalent airspeed measurements. Increasing it reduces the weighting on these measurements. + // @Description: This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements. // @Range: 0.5 5.0 // @Increment: 0.1 // @User: Advanced