From 0cbba4fdd0827e7ae453a85f986a532f096f6a70 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 17 Aug 2022 11:10:53 +0900 Subject: [PATCH] AP_Proximity: distance_min/max checks all backends --- libraries/AP_Proximity/AP_Proximity.cpp | 33 +++++++++++++++++++------ 1 file changed, 25 insertions(+), 8 deletions(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index a0fa739ac5..725deae794 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/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 float AP_Proximity::distance_max() const { - if (!valid_instance(primary_instance)) { - return 0.0f; + float dist_max = 0; + + // return longest distance from all backends + for (uint8_t i=0; idistance_max()); + } } - // get maximum distance from backend - return drivers[primary_instance]->distance_max(); + return dist_max; } float AP_Proximity::distance_min() const { - if (!valid_instance(primary_instance)) { - return 0.0f; + float dist_min = 0; + bool found_dist_min = false; + + // calculate shortest distance from all backends + for (uint8_t i=0; idistance_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 drivers[primary_instance]->distance_min(); + return 0; }