mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Proximity: SF40c driver treats zero distances as invalid
This commit is contained in:
parent
33231bf9b5
commit
458449eca8
@ -411,7 +411,7 @@ bool AP_Proximity_LightWareSF40C::process_reply()
|
||||
if (convert_angle_to_sector(angle_deg, sector)) {
|
||||
_angle[sector] = angle_deg;
|
||||
_distance[sector] = distance_m;
|
||||
_distance_valid[sector] = true;
|
||||
_distance_valid[sector] = is_positive(distance_m);
|
||||
_last_distance_received_ms = AP_HAL::millis();
|
||||
success = true;
|
||||
// update boundary used for avoidance
|
||||
|
Loading…
Reference in New Issue
Block a user