mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Proximity: Use 3 sectors for simple avoidance boundary
This commit is contained in:
parent
8cab737bdd
commit
f107ce3951
@ -189,11 +189,11 @@ bool AP_Proximity_Boundary_3D::convert_obstacle_num_to_face(uint8_t obstacle_num
|
||||
face.sector = sector;
|
||||
face.layer = layer;
|
||||
|
||||
uint8_t valid_sector = sector;
|
||||
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
|
||||
// update boundary has manipulated this face
|
||||
return true;
|
||||
}
|
||||
valid_sector = get_next_sector(valid_sector);
|
||||
|
Loading…
Reference in New Issue
Block a user