mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
GCS_Mavlink: scale across full valid range
This commit is contained in:
parent
1856722b65
commit
617024bdfa
@ -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()
|
||||
|
Loading…
Reference in New Issue
Block a user