GCS_Mavlink: scale across full valid range

This commit is contained in:
olliw42 2021-08-25 04:45:42 +02:00 committed by Peter Barker
parent 1856722b65
commit 617024bdfa
1 changed files with 2 additions and 2 deletions

View File

@ -5487,8 +5487,8 @@ uint8_t GCS_MAVLINK::receiver_rssi() const
return 255;
}
uint8_t rssi = aprssi->read_receiver_rssi() * 255;
return (rssi < 255) ? rssi : 254;
// scale across the full valid range
return aprssi->read_receiver_rssi() * 254;
}
GCS &gcs()