AP_Proximity: Check for valid reading before pushing to OA DB

This commit is contained in:
Rishabh 2020-07-10 03:04:26 +05:30 committed by Randy Mackay
parent 05416daef3
commit 8e586bc67d

View File

@ -174,7 +174,7 @@ void AP_Proximity_Backend::update_boundary_for_sector(const uint8_t sector, cons
return; return;
} }
if (push_to_OA_DB) { if (push_to_OA_DB && _distance_valid[sector]) {
database_push(_angle[sector], _distance[sector]); database_push(_angle[sector], _distance[sector]);
} }