AP_RCProtocol: fix fport rssi

This commit is contained in:
yaapu 2020-09-25 08:57:35 +02:00 committed by Andrew Tridgell
parent 7398529f6b
commit f33d197b16
1 changed files with 2 additions and 2 deletions

View File

@ -124,8 +124,8 @@ void AP_RCProtocol_FPort::decode_control(const FPort_Frame &frame)
bool failsafe = ((frame.control.flags & (1 << FLAGS_FAILSAFE_BIT)) != 0);
// we scale rssi by 2x to make it match the value displayed in OpenTX
const uint8_t scaled_rssi = MIN(frame.control.rssi*2, 255);
// fport rssi 0-50, ardupilot rssi 0-255, scale factor 255/50=5.1
const uint8_t scaled_rssi = MIN(frame.control.rssi * 5.1f, 255);
add_input(MAX_CHANNELS, values, failsafe, scaled_rssi);
}