From 25f327c4ac8ee9504de31688a97568c0885971e3 Mon Sep 17 00:00:00 2001 From: Lorenz Meier Date: Sat, 23 Apr 2016 16:33:25 +0200 Subject: [PATCH] Set RSSI to zero if we loose signal --- src/modules/mavlink/mavlink_messages.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 29b0495ad4..c25001aafc 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -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);