From dca9e3bfa03a139d30d4a3cc4a2ab5f1635ed42b Mon Sep 17 00:00:00 2001 From: Nate Weibley Date: Tue, 24 Nov 2015 14:33:14 -0500 Subject: [PATCH] Fix SI1K radio RSSI calculation to correctly represent received power --- src/comm/MAVLinkProtocol.cc | 19 ++++++++++++++++++- src/comm/MAVLinkProtocol.h | 4 ++-- src/ui/toolbar/MainToolBarController.cc | 10 ++++------ src/ui/toolbar/MainToolBarIndicators.qml | 4 ++-- 4 files changed, 26 insertions(+), 11 deletions(-) diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 7d3f12119..115021b1e 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -291,8 +291,25 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) // process telemetry status message mavlink_radio_status_t rstatus; mavlink_msg_radio_status_decode(&message, &rstatus); + int rssi = rstatus.rssi, + remrssi = rstatus.remrssi; + // 3DR Si1k radio needs rssi fields to be converted to dBm + if (message.sysid == '3' && message.compid == 'D') { + /* Per the Si1K datasheet figure 23.25 and SI AN474 code + * samples the relationship between the RSSI register + * and received power is as follows: + * + * 10 + * inputPower = rssi * ------ 127 + * 19 + * + * Additionally limit to the only realistic range [-120,0] dBm + */ + rssi = qMin(qMax(qRound(static_cast(rssi) / 1.9 - 127.0), - 120), 0); + remrssi = qMin(qMax(qRound(static_cast(remrssi) / 1.9 - 127.0), - 120), 0); + } - emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rstatus.rssi, rstatus.remrssi, + emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rssi, remrssi, rstatus.txbuf, rstatus.noise, rstatus.remnoise); } diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index 71d0af95d..b24491ee6 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -269,8 +269,8 @@ signals: * * @param rxerrors receive errors * @param fixed count of error corrected packets - * @param rssi local signal strength - * @param remrssi remote signal strength + * @param rssi local signal strength in dBm + * @param remrssi remote signal strength in dBm * @param txbuf how full the tx buffer is as a percentage * @param noise background noise level * @param remnoise remote background noise level diff --git a/src/ui/toolbar/MainToolBarController.cc b/src/ui/toolbar/MainToolBarController.cc index bc3c1ab0c..e19dfe9e3 100644 --- a/src/ui/toolbar/MainToolBarController.cc +++ b/src/ui/toolbar/MainToolBarController.cc @@ -98,14 +98,12 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, int rssi, int remrssi, unsigned, unsigned, unsigned) { - if((unsigned)_telemetryLRSSI != rssi) { - // According to the Silabs data sheet, the RSSI value is 0.5db per bit - _telemetryLRSSI = rssi >> 1; + if(_telemetryLRSSI != rssi) { + _telemetryLRSSI = rssi; emit telemetryLRSSIChanged(_telemetryLRSSI); } - if((unsigned)_telemetryRRSSI != remrssi) { - // According to the Silabs data sheet, the RSSI value is 0.5db per bit - _telemetryRRSSI = remrssi >> 1; + if(_telemetryRRSSI != remrssi) { + _telemetryRRSSI = remrssi; emit telemetryRRSSIChanged(_telemetryRRSSI); } } diff --git a/src/ui/toolbar/MainToolBarIndicators.qml b/src/ui/toolbar/MainToolBarIndicators.qml index 909175dfd..4637a9d6c 100644 --- a/src/ui/toolbar/MainToolBarIndicators.qml +++ b/src/ui/toolbar/MainToolBarIndicators.qml @@ -536,7 +536,7 @@ Row { color: colorWhite } QGCLabel { - text: _controller.telemetryRRSSI + 'dB' + text: _controller.telemetryRRSSI + 'dBm' width: getProportionalDimmension(30) horizontalAlignment: Text.AlignRight font.pixelSize: ScreenTools.smallFontPixelSize @@ -553,7 +553,7 @@ Row { color: colorWhite } QGCLabel { - text: _controller.telemetryLRSSI + 'dB' + text: _controller.telemetryLRSSI + 'dBm' width: getProportionalDimmension(30) horizontalAlignment: Text.AlignRight font.pixelSize: ScreenTools.smallFontPixelSize -- 2.22.0