Browse Source

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
QGC4.4
davidsastresas 2 years ago committed by Patrick José Pereira
parent
commit
6f1fa9593c
  1. 7
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  2. 2
      src/ui/toolbar/RCRSSIIndicator.qml

7
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -954,9 +954,10 @@ void APMFirmwarePlugin::_handleRCChannels(Vehicle* vehicle, mavlink_message_t* m
mavlink_rc_channels_t channels; mavlink_rc_channels_t channels;
mavlink_msg_rc_channels_decode(message, &channels); mavlink_msg_rc_channels_decode(message, &channels);
//-- Ardupilot uses 0-255 to indicate 0-100% where QGC expects 0-100 //-- Ardupilot uses 0-254 to indicate 0-100% where QGC expects 0-100
if(channels.rssi) { // As per mavlink specs, 255 means invalid, we must leave it like that for indicators to hide if no rssi data
channels.rssi = static_cast<uint8_t>(static_cast<double>(channels.rssi) / 255.0 * 100.0); if(channels.rssi && channels.rssi != 255) {
channels.rssi = static_cast<uint8_t>(static_cast<double>(channels.rssi) / 254.0 * 100.0);
} }
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_msg_rc_channels_encode_chan( mavlink_msg_rc_channels_encode_chan(

2
src/ui/toolbar/RCRSSIIndicator.qml

@ -24,7 +24,7 @@ Item {
anchors.top: parent.top anchors.top: parent.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom
property bool showIndicator: _activeVehicle.supportsRadio property bool showIndicator: _activeVehicle.supportsRadio && _rcRSSIAvailable
property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle property var _activeVehicle: QGroundControl.multiVehicleManager.activeVehicle
property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false property bool _rcRSSIAvailable: _activeVehicle ? _activeVehicle.rcRSSI > 0 && _activeVehicle.rcRSSI <= 100 : false

Loading…
Cancel
Save