From 2d2e5d69662a41a42562bc941a7d03ea8de31099 Mon Sep 17 00:00:00 2001 From: Andy Piper Date: Wed, 11 Sep 2024 18:51:39 +0100 Subject: [PATCH] AP_RCProtocol: only update rc value for GHST on rc frames --- libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp index 9004355d8c..66493ed88d 100644 --- a/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp +++ b/libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp @@ -280,6 +280,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() const RadioFrame* radio_frame = (const RadioFrame*)(&_frame.payload); const Channels12Bit_4Chan* channels = &(radio_frame->channels); const uint8_t* lowres_channels = radio_frame->lowres_channels; + bool rc_frame = false; // Scaling from Betaflight // Scaling 12bit channels (8bit channels in brackets) @@ -328,6 +329,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[1]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[3]); + rc_frame = true; break; } case GHST_UL_RC_CHANS_HS4_12_5TO8: @@ -338,6 +340,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[1]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[3]); + rc_frame = true; break; } case GHST_UL_RC_CHANS_RSSI: @@ -355,7 +358,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet() } #endif - return true; + return rc_frame; } // send out telemetry