AP_OSD: make rangefinder ranges m rather than cm

This commit is contained in:
Sebastian Quilter 2021-10-18 16:45:33 +11:00 committed by Peter Barker
parent 7da5d9861a
commit c8434fe1ed

View File

@ -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) { if (rangefinder->status_orient(ROTATION_PITCH_270) <= RangeFinder::Status::NoData) {
backend->write(x, y, false, "%c----%c", SYMBOL(SYM_RNGFD), u_icon(DISTANCE)); backend->write(x, y, false, "%c----%c", SYMBOL(SYM_RNGFD), u_icon(DISTANCE));
} else { } 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"; 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)); backend->write(x, y, false, format, SYMBOL(SYM_RNGFD), u_scale(DISTANCE, distance), u_icon(DISTANCE));
} }