AP_Proximity: Integrate the judgment

This commit is contained in:
murata 2021-04-17 20:19:00 +09:00 committed by Randy Mackay
parent 323cbe47d2
commit 7d3a1739d8
1 changed files with 1 additions and 1 deletions

View File

@ -150,7 +150,7 @@ void AP_Proximity_TeraRangerTowerEvo::update_sector_data(int16_t angle_deg, uint
// Get location on 3-D boundary based on angle to the object
const AP_Proximity_Boundary_3D::Face face = boundary.get_face(angle_deg);
//check for target too far, target too close and sensor not connected
const bool valid = (distance_cm != 0xffff) && (distance_cm != 0x0000) && (distance_cm != 0x0001);
const bool valid = (distance_cm != 0xffff) && (distance_cm > 0x0001);
if (valid && !check_obstacle_near_ground(angle_deg, distance_cm * 0.001f)) {
boundary.set_face_attributes(face, angle_deg, ((float) distance_cm) / 1000);
// update OA database