From 3a347374c832cabb5e29682258b04aafecc1ee99 Mon Sep 17 00:00:00 2001 From: rishabsingh3003 Date: Mon, 22 Aug 2022 23:23:43 +0530 Subject: [PATCH] AP_Proximity: Cycle through all drivers to check for upward distance --- libraries/AP_Proximity/AP_Proximity.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Proximity/AP_Proximity.cpp b/libraries/AP_Proximity/AP_Proximity.cpp index 6b174b7b2d..54799e05bd 100644 --- a/libraries/AP_Proximity/AP_Proximity.cpp +++ b/libraries/AP_Proximity/AP_Proximity.cpp @@ -392,7 +392,14 @@ bool AP_Proximity::get_upward_distance(uint8_t instance, float &distance) const bool AP_Proximity::get_upward_distance(float &distance) const { - return get_upward_distance(primary_instance, distance); + // get upward distance from backend + for (uint8_t i=0; i