Commit f556caea authored by Gus Grubba's avatar Gus Grubba

Noise and RSSI are negative values.

parent a2150165
...@@ -919,6 +919,8 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message) ...@@ -919,6 +919,8 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message)
mavlink_msg_radio_status_decode(&message, &rstatus); mavlink_msg_radio_status_decode(&message, &rstatus);
int rssi = rstatus.rssi; int rssi = rstatus.rssi;
int remrssi = rstatus.remrssi; int remrssi = rstatus.remrssi;
int lnoise = (int)(int8_t)rstatus.noise;
int rnoise = (int)(int8_t)rstatus.remnoise;
//-- 3DR Si1k radio needs rssi fields to be converted to dBm //-- 3DR Si1k radio needs rssi fields to be converted to dBm
if (message.sysid == '3' && message.compid == 'D') { if (message.sysid == '3' && message.compid == 'D') {
/* Per the Si1K datasheet figure 23.25 and SI AN474 code /* Per the Si1K datasheet figure 23.25 and SI AN474 code
...@@ -933,6 +935,9 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message) ...@@ -933,6 +935,9 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message)
*/ */
rssi = qMin(qMax(qRound(static_cast<qreal>(rssi) / 1.9 - 127.0), - 120), 0); 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); remrssi = qMin(qMax(qRound(static_cast<qreal>(remrssi) / 1.9 - 127.0), - 120), 0);
} else {
rssi = (int)(int8_t)rstatus.rssi;
remrssi = (int)(int8_t)rstatus.remrssi;
} }
//-- Check for changes //-- Check for changes
if(_telemetryLRSSI != rssi) { if(_telemetryLRSSI != rssi) {
...@@ -955,12 +960,12 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message) ...@@ -955,12 +960,12 @@ void Vehicle::_handleRadioStatus(mavlink_message_t& message)
_telemetryTXBuffer = rstatus.txbuf; _telemetryTXBuffer = rstatus.txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer); emit telemetryTXBufferChanged(_telemetryTXBuffer);
} }
if(_telemetryLNoise != rstatus.noise) { if(_telemetryLNoise != lnoise) {
_telemetryLNoise = rstatus.noise; _telemetryLNoise = lnoise;
emit telemetryLNoiseChanged(_telemetryLNoise); emit telemetryLNoiseChanged(_telemetryLNoise);
} }
if(_telemetryRNoise != rstatus.remnoise) { if(_telemetryRNoise != rnoise) {
_telemetryRNoise = rstatus.remnoise; _telemetryRNoise = rnoise;
emit telemetryRNoiseChanged(_telemetryRNoise); emit telemetryRNoiseChanged(_telemetryRNoise);
} }
} }
......
...@@ -307,8 +307,8 @@ public: ...@@ -307,8 +307,8 @@ public:
Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged) Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged) Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged) Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
Q_PROPERTY(unsigned int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged) Q_PROPERTY(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(unsigned int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged) Q_PROPERTY(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
Q_PROPERTY(QVariantList toolBarIndicators READ toolBarIndicators CONSTANT) Q_PROPERTY(QVariantList toolBarIndicators READ toolBarIndicators CONSTANT)
Q_PROPERTY(QVariantList cameraList READ cameraList CONSTANT) Q_PROPERTY(QVariantList cameraList READ cameraList CONSTANT)
...@@ -587,8 +587,8 @@ public: ...@@ -587,8 +587,8 @@ public:
unsigned int telemetryRXErrors () { return _telemetryRXErrors; } unsigned int telemetryRXErrors () { return _telemetryRXErrors; }
unsigned int telemetryFixed () { return _telemetryFixed; } unsigned int telemetryFixed () { return _telemetryFixed; }
unsigned int telemetryTXBuffer () { return _telemetryTXBuffer; } unsigned int telemetryTXBuffer () { return _telemetryTXBuffer; }
unsigned int telemetryLNoise () { return _telemetryLNoise; } int telemetryLNoise () { return _telemetryLNoise; }
unsigned int telemetryRNoise () { return _telemetryRNoise; } int telemetryRNoise () { return _telemetryRNoise; }
bool autoDisarm (); bool autoDisarm ();
Fact* roll (void) { return &_rollFact; } Fact* roll (void) { return &_rollFact; }
...@@ -717,8 +717,8 @@ signals: ...@@ -717,8 +717,8 @@ signals:
void telemetryRXErrorsChanged (unsigned int value); void telemetryRXErrorsChanged (unsigned int value);
void telemetryFixedChanged (unsigned int value); void telemetryFixedChanged (unsigned int value);
void telemetryTXBufferChanged (unsigned int value); void telemetryTXBufferChanged (unsigned int value);
void telemetryLNoiseChanged (unsigned int value); void telemetryLNoiseChanged (int value);
void telemetryRNoiseChanged (unsigned int value); void telemetryRNoiseChanged (int value);
void autoDisarmChanged (void); void autoDisarmChanged (void);
void firmwareMajorVersionChanged(int major); void firmwareMajorVersionChanged(int major);
...@@ -881,8 +881,8 @@ private: ...@@ -881,8 +881,8 @@ private:
uint32_t _telemetryRXErrors; uint32_t _telemetryRXErrors;
uint32_t _telemetryFixed; uint32_t _telemetryFixed;
uint32_t _telemetryTXBuffer; uint32_t _telemetryTXBuffer;
uint32_t _telemetryLNoise; int _telemetryLNoise;
uint32_t _telemetryRNoise; int _telemetryRNoise;
bool _vehicleCapabilitiesKnown; bool _vehicleCapabilitiesKnown;
bool _supportsMissionItemInt; bool _supportsMissionItemInt;
......
...@@ -26,11 +26,7 @@ Item { ...@@ -26,11 +26,7 @@ Item {
width: _hasTelemetry ? telemIcon.width * 1.1 : 0 width: _hasTelemetry ? telemIcon.width * 1.1 : 0
visible: _hasTelemetry visible: _hasTelemetry
//-- SiK Radio: -120 to < 0
//-- Others: > 0 - 100
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _isSiKRadio: _activeVehicle ? _activeVehicle.telemetryLRSSI < 0 : false
property bool _hasTelemetry: _activeVehicle ? _activeVehicle.telemetryLRSSI !== 0 : false property bool _hasTelemetry: _activeVehicle ? _activeVehicle.telemetryLRSSI !== 0 : false
Component { Component {
...@@ -60,9 +56,9 @@ Item { ...@@ -60,9 +56,9 @@ Item {
columns: 2 columns: 2
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
QGCLabel { text: qsTr("Local RSSI:") } QGCLabel { text: qsTr("Local RSSI:") }
QGCLabel { text: _activeVehicle.telemetryLRSSI + _isSiKRadio ? " dBm" : ""} QGCLabel { text: _activeVehicle.telemetryLRSSI + " dBm"}
QGCLabel { text: qsTr("Remote RSSI:") } QGCLabel { text: qsTr("Remote RSSI:") }
QGCLabel { text: _activeVehicle.telemetryRRSSI + _isSiKRadio ? " dBm" : ""} QGCLabel { text: _activeVehicle.telemetryRRSSI + " dBm"}
QGCLabel { text: qsTr("RX Errors:") } QGCLabel { text: qsTr("RX Errors:") }
QGCLabel { text: _activeVehicle.telemetryRXErrors } QGCLabel { text: _activeVehicle.telemetryRXErrors }
QGCLabel { text: qsTr("Errors Fixed:") } QGCLabel { text: qsTr("Errors Fixed:") }
......
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