|
|
|
@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent)
@@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent)
|
|
|
|
|
|
|
|
|
|
// RSSI (didn't like standard connection)
|
|
|
|
|
connect(qgcApp()->toolbox()->mavlinkProtocol(), |
|
|
|
|
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this, |
|
|
|
|
SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned))); |
|
|
|
|
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned)), this, |
|
|
|
|
SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned))); |
|
|
|
|
|
|
|
|
|
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged); |
|
|
|
|
} |
|
|
|
@ -96,16 +96,14 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
@@ -96,16 +96,14 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
|
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned rssi, unsigned remrssi, unsigned, unsigned, unsigned) |
|
|
|
|
void MainToolBarController::_telemetryChanged(LinkInterface*, unsigned, unsigned, int rssi, int remrssi, unsigned, unsigned, unsigned) |
|
|
|
|
{ |
|
|
|
|
if((unsigned)_telemetryLRSSI != rssi) { |
|
|
|
|
// According to the Silabs data sheet, the RSSI value is 0.5db per bit
|
|
|
|
|
_telemetryLRSSI = rssi >> 1; |
|
|
|
|
if(_telemetryLRSSI != rssi) { |
|
|
|
|
_telemetryLRSSI = rssi; |
|
|
|
|
emit telemetryLRSSIChanged(_telemetryLRSSI); |
|
|
|
|
} |
|
|
|
|
if((unsigned)_telemetryRRSSI != remrssi) { |
|
|
|
|
// According to the Silabs data sheet, the RSSI value is 0.5db per bit
|
|
|
|
|
_telemetryRRSSI = remrssi >> 1; |
|
|
|
|
if(_telemetryRRSSI != remrssi) { |
|
|
|
|
_telemetryRRSSI = remrssi; |
|
|
|
|
emit telemetryRRSSIChanged(_telemetryRRSSI); |
|
|
|
|
} |
|
|
|
|
} |
|
|
|
|