mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
AP_Proximity: backend uses modified Boundary_3D interface
This commit is contained in:
parent
ef9bc64bb1
commit
ad899de78c
@ -31,7 +31,7 @@ AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity
|
||||
{
|
||||
}
|
||||
|
||||
// get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
|
||||
// get distances in PROXIMITY_MAX_DIRECTION directions horizontally. used for sending distances to ground station
|
||||
bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
|
||||
{
|
||||
// cycle through all sectors filling in distances and orientations
|
||||
@ -39,10 +39,9 @@ bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Dist
|
||||
bool valid_distances = false;
|
||||
for (uint8_t i=0; i<PROXIMITY_MAX_DIRECTION; i++) {
|
||||
prx_dist_array.orientation[i] = i;
|
||||
const boundary_location bnd_loc{i};
|
||||
if (boundary.check_distance_valid(bnd_loc)) {
|
||||
const AP_Proximity_Boundary_3D::Face face(PROXIMITY_MIDDLE_LAYER, i);
|
||||
if (boundary.get_distance(face, prx_dist_array.distance[i])) {
|
||||
valid_distances = true;
|
||||
prx_dist_array.distance[i] = boundary.get_distance(bnd_loc);
|
||||
} else {
|
||||
prx_dist_array.distance[i] = distance_max();
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user