Browse Source

Copter: RNGFND_FILT param default increased from 0.25 to 0.5

c415-sdk
Randy Mackay 4 years ago committed by Andrew Tridgell
parent
commit
290124720d
  1. 2
      ArduCopter/Parameters.cpp
  2. 2
      ArduCopter/config.h

2
ArduCopter/Parameters.cpp

@ -1063,7 +1063,7 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = { @@ -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

2
ArduCopter/config.h

@ -86,7 +86,7 @@ @@ -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…
Cancel
Save