mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
Copter: RNGFND_FILT param default increased from 0.25 to 0.5
This commit is contained in:
parent
f12a7dd04b
commit
290124720d
@ -1063,7 +1063,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
|
|||||||
// @DisplayName: Rangefinder filter
|
// @DisplayName: Rangefinder filter
|
||||||
// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering
|
// @Description: Rangefinder filter to smooth distance. Set to zero to disable filtering
|
||||||
// @Units: Hz
|
// @Units: Hz
|
||||||
// @Range: 0 50
|
// @Range: 0 5
|
||||||
// @Increment: 0.05
|
// @Increment: 0.05
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
// @RebootRequired: True
|
// @RebootRequired: True
|
||||||
|
@ -86,7 +86,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef RANGEFINDER_FILT_DEFAULT
|
#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
|
#endif
|
||||||
|
|
||||||
#ifndef SURFACE_TRACKING_VELZ_MAX
|
#ifndef SURFACE_TRACKING_VELZ_MAX
|
||||||
|
Loading…
Reference in New Issue
Block a user