Set RSSI to zero if we loose signal

This commit is contained in:
Lorenz Meier
2016-04-23 16:33:25 +02:00
parent 82d51c5d17
commit 25f327c4ac
+1 -1
View File
@@ -2335,7 +2335,7 @@ protected:
msg.chan17_raw = (rc.channel_count > 16) ? rc.values[16] : UINT16_MAX;
msg.chan18_raw = (rc.channel_count > 17) ? rc.values[17] : UINT16_MAX;
msg.rssi = rc.rssi;
msg.rssi = (rc.channel_count > 0) ? rc.rssi : 0;
_mavlink->send_message(MAVLINK_MSG_ID_RC_CHANNELS, &msg);