From 48a3ea0d803ce316712baf5085e09125613adc46 Mon Sep 17 00:00:00 2001 From: dogmaphobic Date: Tue, 21 Apr 2015 10:36:00 -0400 Subject: [PATCH] Changed RC RSSI to follow original spec. --- src/uas/UAS.cc | 24 +----------------------- src/ui/toolbar/MainToolBar.cc | 2 +- src/ui/toolbar/MainToolBar.h | 2 +- src/ui/toolbar/MainToolBar.qml | 2 +- 4 files changed, 4 insertions(+), 26 deletions(-) diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 028ac9a..1b3c0e3 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -923,28 +923,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_rc_channels_t channels; mavlink_msg_rc_channels_decode(&message, &channels); - /* - * Full RSSI field: 0b 1 111 1111 - * | | | - * | | ^ These four bits encode a total of - * | | 16 RSSI levels. 15 = full, 0 = no signal - * | | - * | ^ These three bits encode a total of 8 - * | digital RC input types. - * | 0: PPM, 1: SBUS, 2: Spektrum, 3: ST24 - * | - * ^ If bit is set, RSSI encodes type + RSSI - */ - - // TODO: Because the code on the firmware side never sets rssi to 0 on loss of connection - // we get a minimum value of 1 (3.5dB). This is what it does to compute it: - // msg.rssi |= (rc.rssi <= 100) ? ((rc.rssi / 7) + 1) : 15; - // Therefore, I'm eliminating bit 0 as well. - int tRssi = (channels.rssi & 0x0E) * 7; - if(tRssi > 100) { - tRssi = 100; - } - emit remoteControlRSSIChanged((uint8_t)tRssi); + emit remoteControlRSSIChanged(channels.rssi); if (channels.chan1_raw != UINT16_MAX && channels.chancount > 0) emit remoteControlChannelRawChanged(0, channels.chan1_raw); @@ -994,7 +973,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) const unsigned int portWidth = 8; // XXX magic number - // TODO: This makes an assumption the RSSI has been normalized to 0-100 emit remoteControlRSSIChanged(channels.rssi); if (static_cast(channels.chan1_scaled) != UINT16_MAX) emit remoteControlChannelScaledChanged(channels.port * portWidth + 0, channels.chan1_scaled/10000.0f); diff --git a/src/ui/toolbar/MainToolBar.cc b/src/ui/toolbar/MainToolBar.cc index 25763de..689e154 100644 --- a/src/ui/toolbar/MainToolBar.cc +++ b/src/ui/toolbar/MainToolBar.cc @@ -377,7 +377,7 @@ void MainToolBar::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned } } -void MainToolBar::_remoteControlRSSIChanged(float rssi) +void MainToolBar::_remoteControlRSSIChanged(uint8_t rssi) { // We only care if we haveone single connection if(_connectionCount == 1) { diff --git a/src/ui/toolbar/MainToolBar.h b/src/ui/toolbar/MainToolBar.h index 23e19b3..bd18a7f 100644 --- a/src/ui/toolbar/MainToolBar.h +++ b/src/ui/toolbar/MainToolBar.h @@ -159,7 +159,7 @@ private slots: void _leaveMessageView (); void _setSatLoc (UASInterface* uas, int fix); void _setProgressBarValue (float value); - void _remoteControlRSSIChanged (float rssi); + void _remoteControlRSSIChanged (uint8_t rssi); void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); private: diff --git a/src/ui/toolbar/MainToolBar.qml b/src/ui/toolbar/MainToolBar.qml index 57ad82f..2076169 100644 --- a/src/ui/toolbar/MainToolBar.qml +++ b/src/ui/toolbar/MainToolBar.qml @@ -351,7 +351,7 @@ Rectangle { id: rssiRC width: getProportionalDimmension(55) height: cellHeight - visible: showMavStatus() && mainToolBar.showRSSI + visible: showMavStatus() && mainToolBar.showRSSI && mainToolBar.remoteRSSI <= 100 anchors.verticalCenter: parent.verticalCenter color: getRSSIColor(mainToolBar.remoteRSSI); border.color: "#00000000"