mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OSD: make OSD rssi scale match link quality (0-100)
This commit is contained in:
parent
b112f8dba1
commit
73006d9a7c
@ -1318,7 +1318,7 @@ void AP_OSD_Screen::draw_rssi(uint8_t x, uint8_t y)
|
||||
{
|
||||
AP_RSSI *ap_rssi = AP_RSSI::get_singleton();
|
||||
if (ap_rssi) {
|
||||
const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 99;
|
||||
const uint8_t rssiv = ap_rssi->read_receiver_rssi() * 100;
|
||||
backend->write(x, y, rssiv < osd->warn_rssi, "%c%2d", SYMBOL(SYM_RSSI), rssiv);
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user