Copter: RNGFND_FILT param default increased from 0.25 to 0.5

This commit is contained in:
Randy Mackay 2021-06-25 10:09:55 +09:00 committed by Andrew Tridgell
parent 86e8731fc5
commit 4dee6d2e4b
2 changed files with 2 additions and 2 deletions

View File

@ -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

View File

@ -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