Browse Source

AP_Proximity: distance_min/max checks all backends

master
Randy Mackay 3 years ago committed by Andrew Tridgell
parent
commit
0cbba4fdd0
  1. 33
      libraries/AP_Proximity/AP_Proximity.cpp

33
libraries/AP_Proximity/AP_Proximity.cpp

@ -249,19 +249,36 @@ AP_Proximity::Status AP_Proximity::get_status() const
// get maximum and minimum distances (in meters) of primary sensor // get maximum and minimum distances (in meters) of primary sensor
float AP_Proximity::distance_max() const float AP_Proximity::distance_max() const
{ {
if (!valid_instance(primary_instance)) { float dist_max = 0;
return 0.0f;
// return longest distance from all backends
for (uint8_t i=0; i<num_instances; i++) {
if (valid_instance(i)) {
dist_max = MAX(dist_max, drivers[i]->distance_max());
}
} }
// get maximum distance from backend return dist_max;
return drivers[primary_instance]->distance_max();
} }
float AP_Proximity::distance_min() const float AP_Proximity::distance_min() const
{ {
if (!valid_instance(primary_instance)) { float dist_min = 0;
return 0.0f; bool found_dist_min = false;
// calculate shortest distance from all backends
for (uint8_t i=0; i<num_instances; i++) {
if (valid_instance(i)) {
const float disti_min = drivers[i]->distance_min();
if (!found_dist_min || (disti_min <= dist_min)) {
dist_min = disti_min;
found_dist_min = true;
}
}
}
if (found_dist_min) {
return dist_min;
} }
// get minimum distance from backend return 0;
return drivers[primary_instance]->distance_min();
} }

Loading…
Cancel
Save