Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_RCProtocol: only update rc value for GHST on rc frames #28083

Merged
merged 1 commit into from
Sep 13, 2024
Merged
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion libraries/AP_RCProtocol/AP_RCProtocol_GHST.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down Expand Up @@ -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:
Expand All @@ -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:
Expand All @@ -355,7 +358,7 @@ bool AP_RCProtocol_GHST::decode_ghost_packet()
}
#endif

return true;
return rc_frame;
}

// send out telemetry
Expand Down
Loading