From c8434fe1edfdf6040838e4ad7382196cef0091ad Mon Sep 17 00:00:00 2001 From: Sebastian Quilter Date: Mon, 18 Oct 2021 16:45:33 +1100 Subject: [PATCH] AP_OSD: make rangefinder ranges m rather than cm --- libraries/AP_OSD/AP_OSD_Screen.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_OSD/AP_OSD_Screen.cpp b/libraries/AP_OSD/AP_OSD_Screen.cpp index a95e52ed90..03eb70b841 100644 --- a/libraries/AP_OSD/AP_OSD_Screen.cpp +++ b/libraries/AP_OSD/AP_OSD_Screen.cpp @@ -2141,7 +2141,7 @@ void AP_OSD_Screen::draw_rngf(uint8_t x, uint8_t y) if (rangefinder->status_orient(ROTATION_PITCH_270) <= RangeFinder::Status::NoData) { backend->write(x, y, false, "%c----%c", SYMBOL(SYM_RNGFD), u_icon(DISTANCE)); } else { - const float distance = rangefinder->distance_cm_orient(ROTATION_PITCH_270) * 0.01f; + const float distance = rangefinder->distance_orient(ROTATION_PITCH_270); const char *format = distance < 9.995 ? "%c %1.2f%c" : "%c%2.2f%c"; backend->write(x, y, false, format, SYMBOL(SYM_RNGFD), u_scale(DISTANCE, distance), u_icon(DISTANCE)); }