AP_Proximity: reduce SF45b mode filter to 3 elements

This commit is contained in:
Randy Mackay 2023-02-28 11:45:44 +09:00 committed by Andrew Tridgell
parent e4d60347fb
commit d94236650a
1 changed files with 1 additions and 1 deletions

View File

@ -81,7 +81,7 @@ private:
uint32_t _last_init_ms; // system time of last re-initialisation
uint32_t _last_distance_received_ms; // system time of last distance measurement received from sensor
bool _init_complete; // true once sensor initialisation is complete
ModeFilterInt16_Size5 _distance_filt{2};// mode filter to reduce glitches
ModeFilterInt16_Size3 _distance_filt{1};// mode filter to reduce glitches
// 3D boundary face and distance for latest readings
AP_Proximity_Boundary_3D::Face _face; // face of most recently received distance