From 1226808909d2728ae3211af03277c703745fbd50 Mon Sep 17 00:00:00 2001 From: yaapu Date: Fri, 25 Sep 2020 08:57:35 +0200 Subject: [PATCH] AP_RCProtocol: fix fport rssi --- libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index 3232c55dde..3d5f900f3c 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -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); }