Commit 135d0fac authored by Nate Weibley's avatar Nate Weibley

Allow signed RSSI values for telemetry links as input power will almost certainly be below 0 dBm

parent dbaa604b
...@@ -275,7 +275,7 @@ signals: ...@@ -275,7 +275,7 @@ signals:
* @param noise background noise level * @param noise background noise level
* @param remnoise remote 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); unsigned txbuf, unsigned noise, unsigned remnoise);
/// @brief Emitted when a temporary log file is ready for saving /// @brief Emitted when a temporary log file is ready for saving
......
...@@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent) ...@@ -52,8 +52,8 @@ MainToolBarController::MainToolBarController(QObject* parent)
// RSSI (didn't like standard connection) // RSSI (didn't like standard connection)
connect(qgcApp()->toolbox()->mavlinkProtocol(), connect(qgcApp()->toolbox()->mavlinkProtocol(),
SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned)), this, SIGNAL(radioStatusChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned)), this,
SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned, unsigned))); SLOT(_telemetryChanged(LinkInterface*, unsigned, unsigned, int, int, unsigned, unsigned, unsigned)));
connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged); connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::activeVehicleChanged, this, &MainToolBarController::_activeVehicleChanged);
} }
...@@ -96,7 +96,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) ...@@ -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) { if((unsigned)_telemetryLRSSI != rssi) {
// According to the Silabs data sheet, the RSSI value is 0.5db per bit // According to the Silabs data sheet, the RSSI value is 0.5db per bit
......
...@@ -80,7 +80,7 @@ signals: ...@@ -80,7 +80,7 @@ signals:
private slots: private slots:
void _activeVehicleChanged (Vehicle* vehicle); void _activeVehicleChanged (Vehicle* vehicle);
void _setProgressBarValue (float value); 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); void _delayedShowToolBarMessage (void);
private: private:
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment