From 6f1fa9593c713981154d26307916cec31d4da61c Mon Sep 17 00:00:00 2001 From: davidsastresas Date: Fri, 14 Jul 2023 13:50:38 +0200 Subject: [PATCH] APMFirmwarePlugin, RCRSSIIncidator: solve bug where no valid rssi would show indicator: There was a bug scaling rc rssi from rc_channels mavlink message where it was scaled to 0-100 from 0-255, and this was wrong because 255 is meant to be invalid, and AP uses 0-254 anyway. We must leave 255 as it is so the frontend can understand if we don't have data. Also, in RCRSSIIndicator, we don't show the indicator anymore if data is not valid, there is no point --- src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 7 ++++--- src/ui/toolbar/RCRSSIIndicator.qml | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index f5e3b47..cbc0160 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -954,9 +954,10 @@ void APMFirmwarePlugin::_handleRCChannels(Vehicle* vehicle, mavlink_message_t* m mavlink_rc_channels_t channels; mavlink_msg_rc_channels_decode(message, &channels); - //-- Ardupilot uses 0-255 to indicate 0-100% where QGC expects 0-100 - if(channels.rssi) { - channels.rssi = static_cast(static_cast(channels.rssi) / 255.0 * 100.0); + //-- Ardupilot uses 0-254 to indicate 0-100% where QGC expects 0-100 + // As per mavlink specs, 255 means invalid, we must leave it like that for indicators to hide if no rssi data + if(channels.rssi && channels.rssi != 255) { + channels.rssi = static_cast(static_cast(channels.rssi) / 254.0 * 100.0); } MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); mavlink_msg_rc_channels_encode_chan( diff --git a/src/ui/toolbar/RCRSSIIndicator.qml b/src/ui/toolbar/RCRSSIIndicator.qml index 3d65d62..a4bf7dd 100644 --- a/src/ui/toolbar/RCRSSIIndicator.qml +++ b/src/ui/toolbar/RCRSSIIndicator.qml @@ -24,7 +24,7 @@ Item { anchors.top: parent.top anchors.bottom: parent.bottom - property bool showIndicator: _activeVehicle.supportsRadio + property bool showIndicator: _activeVehicle.supportsRadio && _rcRSSIAvailable property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false