From cef436b2726bfbcb8d3f3ad34dc7353adbc42bad Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 18 Apr 2022 15:50:50 +1000 Subject: [PATCH] AP_RangeFinder: implement distance_cm_orient in terms of distance_orient --- libraries/AP_RangeFinder/AP_RangeFinder.cpp | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/libraries/AP_RangeFinder/AP_RangeFinder.cpp b/libraries/AP_RangeFinder/AP_RangeFinder.cpp index b5af4b54be..b1ba7a7f48 100644 --- a/libraries/AP_RangeFinder/AP_RangeFinder.cpp +++ b/libraries/AP_RangeFinder/AP_RangeFinder.cpp @@ -686,11 +686,7 @@ float RangeFinder::distance_orient(enum Rotation orientation) const uint16_t RangeFinder::distance_cm_orient(enum Rotation orientation) const { - AP_RangeFinder_Backend *backend = find_instance(orientation); - if (backend == nullptr) { - return 0; - } - return backend->distance_cm(); + return distance_orient(orientation) * 100.0; } int16_t RangeFinder::max_distance_cm_orient(enum Rotation orientation) const