diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index b8b4b7564b16b26f788eeaefbf49089b3db4c98b..71d0af95de22726e6dedc9eee36d7079d24b75e1 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -275,7 +275,7 @@ signals: * @param noise background noise level * @param remnoise remote background noise level */ - void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, + void radioStatusChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); /// @brief Emitted when a temporary log file is ready for saving diff --git a/src/ui/toolbar/MainToolBarController.cc b/src/ui/toolbar/MainToolBarController.cc index 2f84d1feb21237321ac973e02df74f1bd736eec0..bc3c1ab0c34bff8ec45bfc4338c0685516e9102d 100644 --- a/src/ui/toolbar/MainToolBarController.cc +++ b/src/ui/toolbar/MainToolBarController.cc @@ -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,7 +96,7 @@ 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 diff --git a/src/ui/toolbar/MainToolBarController.h b/src/ui/toolbar/MainToolBarController.h index 8b3cae72ec74f07d967b268db3bdf3b8e8cfc72d..cb0efc6d75d1b667b7a4403844eec8acfecaafe3 100644 --- a/src/ui/toolbar/MainToolBarController.h +++ b/src/ui/toolbar/MainToolBarController.h @@ -80,7 +80,7 @@ signals: private slots: void _activeVehicleChanged (Vehicle* vehicle); void _setProgressBarValue (float value); - void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, unsigned rssi, unsigned remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); + void _telemetryChanged (LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise); void _delayedShowToolBarMessage (void); private: