From 4dee6d2e4b8bd6ac2989ca2219128ab82ba2280b Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 25 Jun 2021 10:09:55 +0900 Subject: [PATCH] Copter: RNGFND_FILT param default increased from 0.25 to 0.5 --- ArduCopter/Parameters.cpp | 2 +- ArduCopter/config.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 0c2c527e20..26928f5510 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -1063,7 +1063,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { // @DisplayName: Rangefinder filter // @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering // @Units: Hz - // @Range: 0 50 + // @Range: 0 5 // @Increment: 0.05 // @User: Standard // @RebootRequired: True diff --git a/ArduCopter/config.h b/ArduCopter/config.h index c5dd03ba15..5cbe6c15c6 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -86,7 +86,7 @@ #endif #ifndef RANGEFINDER_FILT_DEFAULT - # define RANGEFINDER_FILT_DEFAULT 0.25f // filter for rangefinder distance + # define RANGEFINDER_FILT_DEFAULT 0.5f // filter for rangefinder distance #endif #ifndef SURFACE_TRACKING_VELZ_MAX