mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: RNGFND_FILT param default increased from 0.25 to 0.5
This commit is contained in:
parent
86e8731fc5
commit
4dee6d2e4b
@ -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
|
||||
|
@ -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
|
||||
|
Loading…
Reference in New Issue
Block a user