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