AP_RCProtocol: only update rc value for GHST on rc frames

This commit is contained in:
Andy Piper 2024-09-11 18:51:39 +01:00 committed by Randy Mackay
parent 7f37b83cdd
commit 2e6e020c04
1 changed files with 4 additions and 1 deletions

View File

@ -280,6 +280,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet()
const RadioFrame* radio_frame = (const RadioFrame*)(&_frame.payload); const RadioFrame* radio_frame = (const RadioFrame*)(&_frame.payload);
const Channels12Bit_4Chan* channels = &(radio_frame->channels); const Channels12Bit_4Chan* channels = &(radio_frame->channels);
const uint8_t* lowres_channels = radio_frame->lowres_channels; const uint8_t* lowres_channels = radio_frame->lowres_channels;
bool rc_frame = false;
// Scaling from Betaflight // Scaling from Betaflight
// Scaling 12bit channels (8bit channels in brackets) // 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[1]);
_channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[2]);
_channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[3]); _channels[offset++] = CHANNEL_LR_SCALE_LEGACY(lowres_channels[3]);
rc_frame = true;
break; break;
} }
case GHST_UL_RC_CHANS_HS4_12_5TO8: 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[1]);
_channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[2]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[2]);
_channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[3]); _channels[offset++] = CHANNEL_LR_SCALE(lowres_channels[3]);
rc_frame = true;
break; break;
} }
case GHST_UL_RC_CHANS_RSSI: case GHST_UL_RC_CHANS_RSSI:
@ -355,7 +358,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet()
} }
#endif #endif
return true; return rc_frame;
} }
// send out telemetry // send out telemetry