From 5588229f681494df8b60c57c613c8288e9fc77d0 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 9 Jan 2020 07:08:11 +1100 Subject: [PATCH] AP_RCProtocol: fixed scaling on FPort RSSI make it match OpenTX --- libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp index 2550b3246f..612171d2cf 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_FPort.cpp @@ -22,6 +22,7 @@ #include #include #include +#include extern const AP_HAL::HAL& hal; @@ -116,7 +117,11 @@ void AP_RCProtocol_FPort::decode_control(const FPort_Frame &frame) } bool failsafe = ((frame.control.flags & (1 << FLAGS_FAILSAFE_BIT)) != 0); - add_input(MAX_CHANNELS, values, failsafe, frame.control.rssi); + + // 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); + + add_input(MAX_CHANNELS, values, failsafe, scaled_rssi); } /*