AP_Proximity: Use 3 sectors for simple avoidance boundary

This commit is contained in:
Rishabh 2021-02-11 13:07:51 +05:30 committed by Randy Mackay
parent 8cab737bdd
commit f107ce3951

View File

@ -191,7 +191,7 @@ bool AP_Proximity_Boundary_3D::convert_obstacle_num_to_face(uint8_t obstacle_num
uint8_t valid_sector = sector;
// check for 3 adjacent sectors
for (uint8_t i=0; i < 2; i++) {
for (uint8_t i=0; i < 3; i++) {
if (_distance_valid[layer][valid_sector]) {
// update boundary has manipulated this face
return true;