Commit a2150165 authored by Gus Grubba's avatar Gus Grubba

Move telemetry RSSI handling to within Vehicle.

Fixing the telemetry RSSI indicator.
parent c825e647
......@@ -159,7 +159,6 @@ Vehicle::Vehicle(LinkInterface* link,
_mavlink = qgcApp()->toolbox()->mavlinkProtocol();
connect(_mavlink, &MAVLinkProtocol::messageReceived, this, &Vehicle::_mavlinkMessageReceived);
connect(_mavlink, &MAVLinkProtocol::radioStatusChanged, this, &Vehicle::_telemetryChanged);
connect(this, &Vehicle::_sendMessageOnLinkOnThread, this, &Vehicle::_sendMessageOnLink, Qt::QueuedConnection);
connect(this, &Vehicle::flightModeChanged, this, &Vehicle::_handleFlightModeChanged);
......@@ -428,37 +427,6 @@ void Vehicle::resetCounters()
_heardFrom = false;
}
void Vehicle::_telemetryChanged(LinkInterface*, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise)
{
if(_telemetryLRSSI != rssi) {
_telemetryLRSSI = rssi;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_telemetryRRSSI != remrssi) {
_telemetryRRSSI = remrssi;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_telemetryRXErrors != rxerrors) {
_telemetryRXErrors = rxerrors;
emit telemetryRXErrorsChanged(_telemetryRXErrors);
}
if(_telemetryFixed != fixed) {
_telemetryFixed = fixed;
emit telemetryFixedChanged(_telemetryFixed);
}
if(_telemetryTXBuffer != txbuf) {
_telemetryTXBuffer = txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer);
}
if(_telemetryLNoise != noise) {
_telemetryLNoise = noise;
emit telemetryLNoiseChanged(_telemetryLNoise);
}
if(_telemetryRNoise != remnoise) {
_telemetryRNoise = remnoise;
emit telemetryRNoiseChanged(_telemetryRNoise);
}
}
void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message)
{
......@@ -512,6 +480,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes
case MAVLINK_MSG_ID_HEARTBEAT:
_handleHeartbeat(message);
break;
case MAVLINK_MSG_ID_RADIO_STATUS:
_handleRadioStatus(message);
break;
case MAVLINK_MSG_ID_RC_CHANNELS:
_handleRCChannels(message);
break;
......@@ -941,6 +912,59 @@ void Vehicle::_handleHeartbeat(mavlink_message_t& message)
}
}
void Vehicle::_handleRadioStatus(mavlink_message_t& message)
{
//-- Process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
int rssi = rstatus.rssi;
int 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);
}
//-- Check for changes
if(_telemetryLRSSI != rssi) {
_telemetryLRSSI = rssi;
emit telemetryLRSSIChanged(_telemetryLRSSI);
}
if(_telemetryRRSSI != remrssi) {
_telemetryRRSSI = remrssi;
emit telemetryRRSSIChanged(_telemetryRRSSI);
}
if(_telemetryRXErrors != rstatus.rxerrors) {
_telemetryRXErrors = rstatus.rxerrors;
emit telemetryRXErrorsChanged(_telemetryRXErrors);
}
if(_telemetryFixed != rstatus.fixed) {
_telemetryFixed = rstatus.fixed;
emit telemetryFixedChanged(_telemetryFixed);
}
if(_telemetryTXBuffer != rstatus.txbuf) {
_telemetryTXBuffer = rstatus.txbuf;
emit telemetryTXBufferChanged(_telemetryTXBuffer);
}
if(_telemetryLNoise != rstatus.noise) {
_telemetryLNoise = rstatus.noise;
emit telemetryLNoiseChanged(_telemetryLNoise);
}
if(_telemetryRNoise != rstatus.remnoise) {
_telemetryRNoise = rstatus.remnoise;
emit telemetryRNoiseChanged(_telemetryRNoise);
}
}
void Vehicle::_handleRCChannels(mavlink_message_t& message)
{
mavlink_rc_channels_t channels;
......
......@@ -757,7 +757,6 @@ signals:
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
void _telemetryChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
void _linkInactiveOrDeleted(LinkInterface* link);
void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
void _sendMessageMultipleNext(void);
......@@ -795,6 +794,7 @@ private:
void _startJoystick(bool start);
void _handleHomePosition(mavlink_message_t& message);
void _handleHeartbeat(mavlink_message_t& message);
void _handleRadioStatus(mavlink_message_t& message);
void _handleRCChannels(mavlink_message_t& message);
void _handleRCChannelsRaw(mavlink_message_t& message);
void _handleBatteryStatus(mavlink_message_t& message);
......
......@@ -208,39 +208,6 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
link->setDecodedFirstMavlinkPacket(true);
}
if(message.msgid == MAVLINK_MSG_ID_RADIO_STATUS)
{
// process telemetry status message
mavlink_radio_status_t rstatus;
mavlink_msg_radio_status_decode(&message, &rstatus);
int rssi = rstatus.rssi;
int remrssi = rstatus.remrssi;
int noise = rstatus.noise;
int remnoise = rstatus.remnoise;
// 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);
} else {
rssi = (int8_t) rstatus.rssi;
remrssi = (int8_t) rstatus.remrssi;
noise = (int8_t) rstatus.noise;
remnoise = (int8_t) rstatus.remnoise;
}
emit radioStatusChanged(link, rstatus.rxerrors, rstatus.fixed, rssi, remrssi,
rstatus.txbuf, noise, remnoise);
}
#ifndef __mobile__
// Log data
......
......@@ -20,16 +20,18 @@ import QGroundControl.Palette 1.0
//-------------------------------------------------------------------------
//-- Telemetry RSSI
QGCColoredImage {
anchors.top: parent.top
anchors.bottom: parent.bottom
sourceSize.height: height
source: "/qmlimages/TelemRSSI.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.buttonText
visible: _activeVehicle ? (_activeVehicle.telemetryLRSSI < 0) : false
Item {
anchors.top: parent.top
anchors.bottom: parent.bottom
width: _hasTelemetry ? telemIcon.width * 1.1 : 0
visible: _hasTelemetry
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
//-- SiK Radio: -120 to < 0
//-- Others: > 0 - 100
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _isSiKRadio: _activeVehicle ? _activeVehicle.telemetryLRSSI < 0 : false
property bool _hasTelemetry: _activeVehicle ? _activeVehicle.telemetryLRSSI !== 0 : false
Component {
id: telemRSSIInfo
......@@ -58,9 +60,9 @@ QGCColoredImage {
columns: 2
anchors.horizontalCenter: parent.horizontalCenter
QGCLabel { text: qsTr("Local RSSI:") }
QGCLabel { text: _activeVehicle.telemetryLRSSI + " dBm" }
QGCLabel { text: _activeVehicle.telemetryLRSSI + _isSiKRadio ? " dBm" : ""}
QGCLabel { text: qsTr("Remote RSSI:") }
QGCLabel { text: _activeVehicle.telemetryRRSSI + " dBm" }
QGCLabel { text: _activeVehicle.telemetryRRSSI + _isSiKRadio ? " dBm" : ""}
QGCLabel { text: qsTr("RX Errors:") }
QGCLabel { text: _activeVehicle.telemetryRXErrors }
QGCLabel { text: qsTr("Errors Fixed:") }
......@@ -80,6 +82,16 @@ QGCColoredImage {
}
}
}
QGCColoredImage {
id: telemIcon
anchors.top: parent.top
anchors.bottom: parent.bottom
width: height
sourceSize.height: height
source: "/qmlimages/TelemRSSI.svg"
fillMode: Image.PreserveAspectFit
color: qgcPal.buttonText
}
MouseArea {
anchors.fill: parent
onClicked: {
......
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