Commit 135996b3 authored by Don Gagne's avatar Don Gagne

Merge pull request #2276 from NaterGator/si1k-rssi

Fix telemetry radio RSSI calculation for SI1000 based modems
parents ceaa61ac dca9e3bf
...@@ -291,8 +291,25 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b) ...@@ -291,8 +291,25 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// process telemetry status message // process telemetry status message
mavlink_radio_status_t rstatus; mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &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<qreal>(rssi) / 1.9 - 127.0), - 120), 0);
remrssi = qMin(qMax(qRound(static_cast<qreal>(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); rstatus.txbuf, rstatus.noise, rstatus.remnoise);
} }
......
...@@ -269,13 +269,13 @@ signals: ...@@ -269,13 +269,13 @@ signals:
* *
* @param rxerrors receive errors * @param rxerrors receive errors
* @param fixed count of error corrected packets * @param fixed count of error corrected packets
* @param rssi local signal strength * @param rssi local signal strength in dBm
* @param remrssi remote signal strength * @param remrssi remote signal strength in dBm
* @param txbuf how full the tx buffer is as a percentage * @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level * @param noise background noise level
* @param remnoise remote background noise level * @param remnoise remote background noise level
*/ */
void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi,
unsigned txbuf, unsigned noise, unsigned remnoise); unsigned txbuf, unsigned noise, unsigned remnoise);
/// @brief Emitted when a temporary log file is ready for saving /// @brief Emitted when a temporary log file is ready for saving
......
...@@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent) ...@@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent)
// RSSI (didn't like standard connection) // RSSI (didn't like standard connection)
connect(qgcApp()->toolbox()->mavlinkProtocol(), connect(qgcApp()->toolbox()->mavlinkProtocol(),
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this, SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned)), this,
SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned))); SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned)));
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged);
} }
...@@ -96,16 +96,14 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) ...@@ -96,16 +96,14 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
} }
} }
void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned rssi, unsigned remrssi, unsigned, unsigned, unsigned) void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, int rssi, int remrssi, unsigned, unsigned, unsigned)
{ {
if((unsigned)_telemetryLRSSI != rssi) { if(_telemetryLRSSI != rssi) {
// According to the Silabs data sheet, the RSSI value is 0.5db per bit _telemetryLRSSI = rssi;
_telemetryLRSSI = rssi >> 1;
emit telemetryLRSSIChanged(_telemetryLRSSI); emit telemetryLRSSIChanged(_telemetryLRSSI);
} }
if((unsigned)_telemetryRRSSI != remrssi) { if(_telemetryRRSSI != remrssi) {
// According to the Silabs data sheet, the RSSI value is 0.5db per bit _telemetryRRSSI = remrssi;
_telemetryRRSSI = remrssi >> 1;
emit telemetryRRSSIChanged(_telemetryRRSSI); emit telemetryRRSSIChanged(_telemetryRRSSI);
} }
} }
......
...@@ -80,7 +80,7 @@ signals: ...@@ -80,7 +80,7 @@ signals:
private slots: private slots:
void _activeVehicleChanged (Vehicle* vehicle); void _activeVehicleChanged (Vehicle* vehicle);
void _setProgressBarValue (float value); void _setProgressBarValue (float value);
void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
void _delayedShowToolBarMessage (void); void _delayedShowToolBarMessage (void);
private: private:
......
...@@ -536,7 +536,7 @@ Row { ...@@ -536,7 +536,7 @@ Row {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: _controller.telemetryRRSSI + 'dB' text: _controller.telemetryRRSSI + 'dBm'
width: getProportionalDimmension(30) width: getProportionalDimmension(30)
horizontalAlignment: Text.AlignRight horizontalAlignment: Text.AlignRight
font.pixelSize: ScreenTools.smallFontPixelSize font.pixelSize: ScreenTools.smallFontPixelSize
...@@ -553,7 +553,7 @@ Row { ...@@ -553,7 +553,7 @@ Row {
color: colorWhite color: colorWhite
} }
QGCLabel { QGCLabel {
text: _controller.telemetryLRSSI + 'dB' text: _controller.telemetryLRSSI + 'dBm'
width: getProportionalDimmension(30) width: getProportionalDimmension(30)
horizontalAlignment: Text.AlignRight horizontalAlignment: Text.AlignRight
font.pixelSize: ScreenTools.smallFontPixelSize font.pixelSize: ScreenTools.smallFontPixelSize
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment