AP_OSD: fix pointless multiple/divide

This is scaling code; OSD wants 0 to 99 vs 0 to 255 the uint8_t
function gives.  Use the unerlying 0-1 function in the OSD code in
preference to unscaling it from 255 then scaling to 99
This commit is contained in:
Peter Barker 2020-06-09 12:19:37 +10:00 committed by Peter Barker
parent 0e964a4654
commit 8867457c4f

View File

@ -942,8 +942,7 @@ void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
{
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
if (ap_rssi) {
int rssiv = ap_rssi->read_receiver_rssi_uint8();
rssiv = (rssiv * 99) / 255;
const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 99;
backend->write(x, y, rssiv < osd->warn_rssi, "%c%2d", SYM_RSSI, rssiv);
}
}