diff --git a/libraries/AP_NavEKF2/AP_NavEKF2.cpp b/libraries/AP_NavEKF2/AP_NavEKF2.cpp index 2821437625..613ce7d233 100644 --- a/libraries/AP_NavEKF2/AP_NavEKF2.cpp +++ b/libraries/AP_NavEKF2/AP_NavEKF2.cpp @@ -325,7 +325,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Param: FLOW_DELAY // @DisplayName: Optical Flow measurement delay (msec) // @Description: This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor. - // @Range: 0 250 + // @Range: 0 127 // @Increment: 10 // @User: Advanced // @Units: milliseconds @@ -512,7 +512,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = { // @Param: BCN_DELAY // @DisplayName: Range beacon measurement delay (msec) // @Description: This is the number of msec that the range beacon measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor. - // @Range: 0 250 + // @Range: 0 127 // @Increment: 10 // @User: Advanced // @Units: milliseconds